From c23bbe06d342af374abfcadc08534a0123e13614 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:28:33 +0100 Subject: [PATCH 0001/1086] Update v6.0.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 23f4a1c1b..89bcf881e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_policy(SET CMP0048 NEW) project(S2E LANGUAGES CXX DESCRIPTION "S2E: Spacecraft Simulation Environment" - VERSION 5.3.0 + VERSION 6.0.0 ) cmake_minimum_required(VERSION 3.13) From b19624d1dbdbaf3b4f9260ecfc881d08c0cb1057 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:37:02 +0100 Subject: [PATCH 0002/1086] Delete Singleton --- src/Component/Abstract/Singleton.h | 23 ----------------------- 1 file changed, 23 deletions(-) delete mode 100644 src/Component/Abstract/Singleton.h diff --git a/src/Component/Abstract/Singleton.h b/src/Component/Abstract/Singleton.h deleted file mode 100644 index 85a1a2753..000000000 --- a/src/Component/Abstract/Singleton.h +++ /dev/null @@ -1,23 +0,0 @@ -/** - * @file Singleton.h - * @brief Class to restrict that class that the class can have only one instance at a time - * @note TODO: Is this needed? Currently this is used in StateMachine only. And we need to use other library if we want to use. - */ - -#pragma once - -template -class Singleton { - protected: - Singleton() {} - Singleton(Singleton const&); - ~Singleton() {} - - Singleton& operator=(Singleton const&); - - public: - static T* GetInstance() { - static T instance; - return &instance; - } -}; From 3617ce3929452aa5f1c936f8b4e38a07aa819053 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:37:54 +0100 Subject: [PATCH 0003/1086] Delete StateMachine --- src/Component/Abstract/StateMachine.h | 200 -------------------------- 1 file changed, 200 deletions(-) delete mode 100644 src/Component/Abstract/StateMachine.h diff --git a/src/Component/Abstract/StateMachine.h b/src/Component/Abstract/StateMachine.h deleted file mode 100644 index 68a1ec2a7..000000000 --- a/src/Component/Abstract/StateMachine.h +++ /dev/null @@ -1,200 +0,0 @@ -/** - * @file StateMachine.h - * @brief State Machine - * @note TODO: Is this needed? Currently this is not used. And we need to use other library if we want to use. - */ - -#pragma once -#include -#include -#include - -#include "Singleton.h" - -// 参考 -// https://setuna-kanata.hatenadiary.org/entry/20090225/1235570379 -// https://setuna-kanata.hatenadiary.org/entry/20090226/1235658062 -// http://www.lancarse.co.jp/blog/?p=1039 - -// 実行時のオーバーヘッドを減らすために,CRTPで実装している -// http://agtn.hatenablog.com/entry/2016/06/16/192708 -// https://theolizer.com/cpp-school2/cpp-school2-19/ - -// 最終的にはBoostとかの汎用ライブラリを使った方が維持負担が少ないのでは. - -class Event; -template -class ActionInterface; -template -class StateInterface; -template -class StateMachine; - -// 状態遷移やイベント処理の際に実行されるActionのクラス. -template -class ActionInterface { - public: - virtual void Exe(ContextType* context) = 0; -}; - -// ステートマシンに処理を要求するイベントのクラス. -class Event { - private: - int value_; - - public: - Event(int value) : value_(value) {} - - // std::mapを使用するために演算子をオーバーロード - bool operator==(Event const& e) const { return value_ == e.value_; } - bool operator<(Event const& e) const { return value_ < e.value_; } -}; - -// 状態および状態間の処理や関係を与えるクラス. -template -class StateInterface { - public: - using context_t = ContextType; - using state_t = StateInterface; - using action_t = ActionInterface; - typedef std::map transition_map; - typedef std::map action_map; - - public: - // 現在の実装では,Entry,Exitは遷移の際にChainして呼び出されるが,Exeに関しては,その状態のメンバ関数のみが実行される!! - virtual void Entry() {} - virtual void Exe() {} - virtual void Exit() {} - - protected: - context_t* context_; - state_t* parent_; // 親状態(状態は階層化されている) - string name_; // デバッグ用 - transition_map transition_; - action_map action_; - - protected: - StateInterface(string const& name) : name_(name) {} - - public: - // 階層化された親状態のSetter - void SetParent(state_t* parent, context_t* context) { - this->parent_ = parent; - this->context_ = context; - } - - // 親状態のGetter - StateInterface* GetParent() const { return parent_; } - - public: - void AddTransition(Event const& e, state_t* state) { transition_.insert(std::make_pair(e, state)); } - - bool Transit(Event const& e) { - typename transition_map::iterator it = transition_.find(e); - if (it != transition_.end()) { - context_->ChangeState(it->second, this); - typename action_map::iterator it_action = action_.find(e); - if (it_action != action_.end()) it_action->second->Exe(context_); - return true; - } - return false; - } - - public: - void AddAction(Event const& e, action_t* act) { action_.insert(std::make_pair(e, act)); } -}; - -// 階層化ステートマシンの実装. -template -class StateMachine { - protected: - typedef ContextType context_t; - typedef StateInterface state_t; - typedef ActionInterface action_t; - - protected: - // 開始状態.一意なので,Singletonを継承. - class Start : public state_t, public Singleton { - friend class Singleton; - Start() : state_t("Start") {} // デバッグ用にStateに命名 - }; - // 終了状態.一意なので,Singletonを継承. - class End : public state_t, public Singleton { - friend class Singleton; - End() : state_t("End") {} - }; - - private: - state_t* current_; - - public: - StateMachine() - : current_(Start::GetInstance()) //  Startステートで初期化 - {} - - public: - void Update() { current_->Exe(); } - - void ChangeState(state_t* dest_state, state_t* src_state = 0) { - if (src_state == 0) src_state = current_; - - // 自己遷移 - if (src_state == dest_state) { - src_state->Exit(); - dest_state->Entry(); - return; - } - - // 自己でない場合,状態の木構造を探索して,必要な状態遷移の行動列を生成する. - - typedef std::list state_list; - // src_stateからrootまでの経路 - state_list src_top; - for (state_t* s = src_state; s != 0; s = s->GetParent()) src_top.push_front(s); - // dest_stateからrootまでの経路 - state_list dest_top; - for (state_t* s = dest_state; s != 0; s = s->GetParent()) dest_top.push_front(s); - - // 最も近い共通の親をrootから検索する - state_t* parent = 0; - typename state_list::iterator it_src = src_top.begin(); - typename state_list::iterator it_dest = dest_top.begin(); - while (it_src != src_top.end() && it_dest != dest_top.end()) { - if (*it_src != *it_dest) break; - ++it_src; - ++it_dest; - } - // it_srcが先頭でない時の--it_srcが共通の親 - if (it_src != src_top.begin()) { - --it_src; - parent = *it_src; - } - - // 退場動作.子→親の順にExit - for (state_t* s = current_; s != parent; s = s->GetParent()) s->Exit(); - - // 入場動作.親→子の順にEntry - for (; it_dest != dest_top.end(); ++it_dest) (*it_dest)->Entry(); - - current_ = dest_state; - } - - context_t* Derived() { return static_cast(this); } - - void ProcessEvent(Event const& e) { - // イベントによるtransition - // Exit & Entry でカバーできない特殊処理が必要な遷移を実施. - // ChangeStateした上で,自分で処理できない場合は親に渡す - state_t* s = current_; - while (s != 0 && !s->Transit(e)) // Transitはtransition_が存在するかどうかをBoolで返す.ので,Transitに関しては子は親の処理を実行しない(はず). - s = s->GetParent(); - } - - void AddTransition(state_t* current, Event const& e, state_t* next, action_t* action) { - current->AddTransition(e, next); - if (action) current->AddAction(e, action); - } - - public: - bool is_end() const { return current_ == End::GetInstance(); } -}; From 1a7af94e4da053f52778b402ab44ad5a9130458c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:39:16 +0100 Subject: [PATCH 0004/1086] Delete S2E_parallel --- src/S2E_parallel.cpp | 70 -------------------------------------------- 1 file changed, 70 deletions(-) delete mode 100644 src/S2E_parallel.cpp diff --git a/src/S2E_parallel.cpp b/src/S2E_parallel.cpp deleted file mode 100644 index 1e0f26e02..000000000 --- a/src/S2E_parallel.cpp +++ /dev/null @@ -1,70 +0,0 @@ -/** - * @file S2E_parallel.cpp - * @brief The main file of S2E parallel execution - */ - -#include -#include -#include - -#include - -#include "src/Interface/HilsInOut/COSMOSWrapper.h" -#include "src/Interface/HilsInOut/HardwareMessage.h" -#include "src/Interface/InitInput/Initialize.h" -#include "src/Interface/LogOutput/Logger.h" -#include "src/Simulation/Case/EquuleusCase.h" -#include "src/Simulation/Case/SimulationCase.h" -#include "src/Simulation/MCSim/MCSimExecutor.h" - -using namespace System::Threading::Tasks; - -void mail_loop(int idx); - -string ini_fname = "data/ini/SimBase.ini"; - -MCSimExecutor* mc_sim; - -int _tmain_parallel(int argc, _TCHAR* argv[]) { - mc_sim = InitMCSim("data/ini/SimBase.ini"); - Logger mclog("mont.csv"); - - // Monte-Carlo Simulation - // while (mc_sim->WillExecuteNextCase()) - // concurrency::parallel_for(0, mc_sim->GetTotalNumOfExecutions(), //(auto - // i=0; iGetTotalNumOfExecutions(); i++) - Parallel::For(0, mc_sim->GetTotalNumOfExecutions(), gcnew System::Action(mail_loop)); - return 0; - //{ - // SimulationCase& simcase = EquuleusCase(*mc_sim, ini_fname); - // mclog.AddLoggable(&simcase); - // if (mc_sim->GetNumOfExecutionsDone() == 0) - // { - // mclog.WriteHeaders(); - // } - // simcase.Initialize(); - - // mclog.WriteValues(); - // simcase.Main(); - // mclog.WriteValues(); - // mclog.ClearLoggables(); - //} -} - -void mail_loop(int idx) { - COSMOSWrapper& cosmos_wrapper = COSMOSWrapper(); - HardwareMessage& hw_msg = HardwareMessage(); - - SimulationCase& simcase = EquuleusCase(*mc_sim, ini_fname, cosmos_wrapper, hw_msg); - // mclog.AddLoggable(&simcase); - // if (mc_sim->GetNumOfExecutionsDone() == 0) - //{ - // mclog.WriteHeaders(); - // } - simcase.Initialize(); - - // mclog.WriteValues(); - simcase.Main(); - // mclog.WriteValues(); - // mclog.ClearLoggables(); -} From dcef013212b0d2acb2fcb24d2e3efa6f59bc9786 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:42:50 +0100 Subject: [PATCH 0005/1086] Delete EMDS --- src/Component/AOCS/EMDS.cpp | 144 -------------------------------- src/Component/AOCS/EMDS.h | 53 ------------ src/Component/AOCS/InitEmds.cpp | 21 ----- src/Component/AOCS/InitEmds.hpp | 14 ---- src/Component/CMakeLists.txt | 2 - 5 files changed, 234 deletions(-) delete mode 100644 src/Component/AOCS/EMDS.cpp delete mode 100644 src/Component/AOCS/EMDS.h delete mode 100644 src/Component/AOCS/InitEmds.cpp delete mode 100644 src/Component/AOCS/InitEmds.hpp diff --git a/src/Component/AOCS/EMDS.cpp b/src/Component/AOCS/EMDS.cpp deleted file mode 100644 index c40d30945..000000000 --- a/src/Component/AOCS/EMDS.cpp +++ /dev/null @@ -1,144 +0,0 @@ -/** - * @file EMDS.cpp - * @brief Class to emulate Electro Magnetic Docking System - * @note This class is not managed now. TODO: Consider to delete. - */ - -#include "EMDS.h" - -#include - -EMDS::EMDS(Vector<3> mm, Vector<3> displacement) : mm_(mm), dis_(displacement) {} - -EMDS::~EMDS() {} - -void EMDS::Update(EMDS& other) { - if (!IsCalcEnabled) return; - Vector<3> results[4]; - calc(pos_, other.pos_, q_, other.q_, dis_, other.dis_, i_ampere, other.i_ampere, results); - force_b_ = results[0]; - other.force_b_ = results[1]; - torque_b_ = results[2]; - other.torque_b_ = results[3]; -} - -std::string EMDS::GetLogHeader() const { - std::string str_tmp = ""; - - str_tmp += WriteVector("emds_force", "b", "N", 3); - str_tmp += WriteVector("emds_torque", "b", "Nm", 3); - - return str_tmp; -} - -std::string EMDS::GetLogValue() const { - std::string str_tmp = ""; - - str_tmp += WriteVector(force_b_); - str_tmp += WriteVector(torque_b_); - - return str_tmp; -} - -void EMDS::SetParameters(Vector<3> position, Quaternion quaternion, double current) { - force_b_ *= 0; - torque_b_ *= 0; - pos_ = position; - q_ = quaternion; - i_ampere = current; -} - -void EMDS::calc(Vector<3> d1_i, Vector<3> d2_i, Quaternion q1_ib, Quaternion q2_ib, Vector<3> r1_b, Vector<3> r2_b, double i1, double i2, - Vector<3>* results) { - if (i2 >= 0) { - calc_approx(d1_i, d2_i, q1_ib, q2_ib, r1_b, r2_b, i1, i2, 0.23, results); - } - - else if (i2 < 0) { - calc_approx(d1_i, d2_i, q1_ib, q2_ib, r1_b, r2_b, i1, i2, 0.05, results); - } - - // 発散しないよう、適当な値でクリップする - double clipThres = 10.0; - for (int i = 0; i < 4; i++) { - if (norm(results[i]) >= clipThres) results[i] = clipThres * normalize(results[i]); - } -} - -void EMDS::calc_approx(Vector<3> d1_i, Vector<3> d2_i, Quaternion q1_ib, Quaternion q2_ib, Vector<3> r1_b, Vector<3> r2_b, double i1, double i2, - double m_c0, Vector<3>* results) { - using libra::pi; - - const double mu_0 = 4e-7 * pi; - Vector<3> m1_mb(0); - m1_mb[1] = 4.965; // magnetic moment of neodymium - // double m_c0 = 0.23; // offset of coil magnet moment (both 1 and 2) - - double m_cd = (0.3 - m_c0) / 5.0; // Slope of coil magnetic moment change - Vector<3> m1_cb(0); - m1_cb[1] = m_c0 + m_cd * i1; // Magnetic moment of coil - Vector<3> m1_b = m1_mb + m1_cb; // Magnetic moment of spacecraft 1 - Vector<3> m2_b(0); - m2_b[2] = m_c0 + m_cd * i2; // Magnetic moment of spacecraft 2 - m1_b *= -1; // 母機側を反転 - - // Calculate rotation angle - double theta1 = 2 * acos(q1_ib[3]); - double theta2 = 2 * acos(q2_ib[3]); - - // Calculate rotation axis - Vector<3> n1; - n1[0] = q1_ib[0]; - n1[1] = q1_ib[1]; - n1[2] = q1_ib[2]; - Vector<3> n2; - n2[0] = q2_ib[0]; - n2[1] = q2_ib[1]; - n2[2] = q2_ib[2]; - normalize(n1); - normalize(n2); - - // Coordinate transformation of magnetic moment - Vector<3> mu1_i = dot(m1_b, n1) * n1 + cos(theta1) * (m1_b - dot(m1_b, n1) * n1) + sin(theta1) * cross(n1, m1_b); - Vector<3> mu2_i = dot(m2_b, n2) * n2 + cos(theta2) * (m2_b - dot(m2_b, n2) * n2) + sin(theta2) * cross(n2, m2_b); - - // Coordinate transformation of position vector - Vector<3> r1_i = dot(r1_b, n1) * n1 + cos(theta1) * (r1_b - dot(r1_b, n1) * n1) + sin(theta1) * cross(n1, r1_b); - Vector<3> r2_i = dot(r2_b, n2) * n2 + cos(theta2) * (r2_b - dot(r2_b, n2) * n2) + sin(theta2) * cross(n2, r2_b); - - // Calculate relative position - Vector<3> dh = (d2_i + r2_i) - (d1_i + r1_i); - Vector<3> d = dh; - normalize(d); - - // Calculate magnetic force - Vector<3> F1_i = 3.0 * mu_0 / (4.0 * pi * pow(norm(-dh), 4)) * - (dot(mu1_i, -d) * mu2_i + dot(mu2_i, -d) * mu1_i + dot(mu1_i, mu2_i) * (-d) - 5 * dot(mu1_i, -d) * dot(mu2_i, -d) * (-d)); - Vector<3> F2_i = 3.0 * mu_0 / (4.0 * pi * pow(norm(dh), 4)) * - (dot(mu2_i, d) * mu1_i + dot(mu1_i, d) * mu2_i + dot(mu2_i, mu1_i) * (d)-5 * dot(mu2_i, d) * dot(mu1_i, d) * (d)); - - // Calculate the magnet field from magnetic moment - Vector<3> B1_i = mu_0 / (4 * pi * pow(norm(-dh), 3)) * (3 * dot(mu2_i, -d) * (-d) - mu2_i); - Vector<3> B2_i = mu_0 / (4 * pi * pow(norm(dh), 3)) * (3 * dot(mu1_i, d) * (d)-mu1_i); - - // Calculate magnetic torque - Vector<3> tau1_m_i = cross(mu1_i, B1_i); - Vector<3> tau2_m_i = cross(mu2_i, B2_i); - - // Calculate force torque - Vector<3> tau1_F_i = cross(r1_i, F1_i); - Vector<3> tau2_F_i = cross(r2_i, F2_i); - - // Total the torques - Vector<3> tau1_i = tau1_m_i + tau1_F_i; - Vector<3> tau2_i = tau2_m_i + tau2_F_i; - - // Rotate the torque vectors - Vector<3> tau1_b = dot(tau1_i, n1) * n1 + cos(-theta1) * (tau1_i - dot(tau1_i, n1) * n1) + sin(-theta1) * cross(n1, tau1_i); - Vector<3> tau2_b = dot(tau2_i, n2) * n2 + cos(-theta2) * (tau2_i - dot(tau2_i, n2) * n2) + sin(-theta2) * cross(n2, tau2_i); - - results[0] = q1_ib.frame_conv(F1_i); - results[1] = q2_ib.frame_conv(F2_i); - results[2] = tau1_b; - results[3] = tau2_b; -} diff --git a/src/Component/AOCS/EMDS.h b/src/Component/AOCS/EMDS.h deleted file mode 100644 index dac25d25c..000000000 --- a/src/Component/AOCS/EMDS.h +++ /dev/null @@ -1,53 +0,0 @@ -/** - * @file EMDS.h - * @brief Class to emulate Electro Magnetic Docking System - * @note This class is not managed now. TODO: Consider to delete. - */ - -#pragma once - -#include - -#include -#include - -class EMDS : public ILoggable { - public: - bool IsCalcEnabled = true; - - EMDS(Vector<3> mm, Vector<3> displacement); - ~EMDS(); - void Update(EMDS& other); - inline Vector<3> GetTorque_b() { return torque_b_; } - inline Vector<3> GetForce_b() { return force_b_; } - - virtual std::string GetLogHeader() const; - virtual std::string GetLogValue() const; - - // position: position of C.G. of s/c in inertia frame - // quaternion: quaternion from inertia to body frame - // current: electric current in ampere - void SetParameters(Vector<3> position, Quaternion quaternion, double current); - - private: - void calc(Vector<3> d1_i, Vector<3> d2_i, Quaternion q1_ib, Quaternion q2_ib, Vector<3> r1_b, Vector<3> r2_b, double i1, double i2, - Vector<3>* results); - void calc_approx(Vector<3> d1_i, Vector<3> d2_i, Quaternion q1_ib, Quaternion q2_ib, Vector<3> r1_b, Vector<3> r2_b, double i1, double i2, - double m_c0, Vector<3>* results); - - Vector<3> torque_b_ = Vector<3>(0); - Vector<3> force_b_ = Vector<3>(0); - Vector<3> mm_; - - // displacement - Vector<3> dis_; - - // position(inertia frame) - Vector<3> pos_; - - // quaternion(inertia to body) - Quaternion q_; - - // electric current - double i_ampere; -}; diff --git a/src/Component/AOCS/InitEmds.cpp b/src/Component/AOCS/InitEmds.cpp deleted file mode 100644 index ceb7e7750..000000000 --- a/src/Component/AOCS/InitEmds.cpp +++ /dev/null @@ -1,21 +0,0 @@ -/** - * @file InitEmds.cpp - * @brief Initialize functions for EMDS - */ -#include "InitEmds.hpp" - -#include "Interface/InitInput/IniAccess.h" - -EMDS InitEMDS(int actuator_id) { - IniAccess emds_conf("data/ini/component/EMDS.ini"); - - std::string section = "EMDS" + std::to_string(actuator_id); - - Vector<3> displacement; - emds_conf.ReadVector(section.c_str(), "displacement", displacement); - - Vector<3> mm; - - EMDS emds(mm, displacement); - return emds; -} diff --git a/src/Component/AOCS/InitEmds.hpp b/src/Component/AOCS/InitEmds.hpp deleted file mode 100644 index 62d874188..000000000 --- a/src/Component/AOCS/InitEmds.hpp +++ /dev/null @@ -1,14 +0,0 @@ -/** - * @file InitEmds.hpp - * @brief Initialize functions for EMDS - */ -#pragma once - -#include - -/** - * @fn InitEMDS - * @brief Initialize functions for EMDS - * @param [in] actuator_id: Actuator ID - */ -EMDS InitEMDS(int actuator_id); diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index b82ae6465..25ace7726 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -12,8 +12,6 @@ add_library(${PROJECT_NAME} STATIC Abstract/ExpHilsI2cController.cpp Abstract/ExpHilsI2cTarget.cpp - AOCS/EMDS.cpp - AOCS/InitEmds.cpp AOCS/Gyro.cpp AOCS/InitGyro.cpp AOCS/MagSensor.cpp From 728d5fb47d680a7561653f82c5ba5352a6d9d3d7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:43:58 +0100 Subject: [PATCH 0006/1086] Delete RWModule --- src/Component/AOCS/RWModule.cpp | 81 --------------------------------- src/Component/AOCS/RWModule.h | 36 --------------- 2 files changed, 117 deletions(-) delete mode 100644 src/Component/AOCS/RWModule.cpp delete mode 100644 src/Component/AOCS/RWModule.h diff --git a/src/Component/AOCS/RWModule.cpp b/src/Component/AOCS/RWModule.cpp deleted file mode 100644 index 7dca95002..000000000 --- a/src/Component/AOCS/RWModule.cpp +++ /dev/null @@ -1,81 +0,0 @@ -/* - * @file RWModule.cpp - * @brief Class to combine four reaction wheels - * @note We recommend not to use this class. Users can make multiple RW by making multiple instances of RWModel. TODO: Delete this class. - */ - -#include "RWModule.h" - -#include -#include -using namespace libra; - -RWModule::RWModule() {} -RWModule::RWModule(double step_width, double angular_velocity_init_0, double inertia_0, double angular_velocity_upperlimit_init_0, - double angular_velocity_lowerlimit_init_0, bool motor_drive_init_0, double angular_accelaration_init_0, - double angular_velocity_init_1, double inertia_1, double angular_velocity_upperlimit_init_1, - double angular_velocity_lowerlimit_init_1, bool motor_drive_init_1, double angular_accelaration_init_1, - double angular_velocity_init_2, double inertia_2, double angular_velocity_upperlimit_init_2, - double angular_velocity_lowerlimit_init_2, bool motor_drive_init_2, double angular_accelaration_init_2, - double angular_velocity_init_3, double inertia_3, double angular_velocity_upperlimit_init_3, - double angular_velocity_lowerlimit_init_3, bool motor_drive_init_3, double angular_accelaration_init_3, int number_of_RW, - Matrix<3, 4> torque_transition) { - if (number_of_RW == 4) { - RWModel RW0_temp(step_width, angular_velocity_init_0, inertia_0, angular_velocity_upperlimit_init_0, angular_velocity_lowerlimit_init_0, - motor_drive_init_0, angular_accelaration_init_0); - RWModel RW1_temp(step_width, angular_velocity_init_1, inertia_1, angular_velocity_upperlimit_init_1, angular_velocity_lowerlimit_init_1, - motor_drive_init_1, angular_accelaration_init_1); - RWModel RW2_temp(step_width, angular_velocity_init_2, inertia_2, angular_velocity_upperlimit_init_2, angular_velocity_lowerlimit_init_2, - motor_drive_init_2, angular_accelaration_init_2); - RWModel RW3_temp(step_width, angular_velocity_init_3, inertia_3, angular_velocity_upperlimit_init_3, angular_velocity_lowerlimit_init_3, - motor_drive_init_3, angular_accelaration_init_3); - RW_[0] = RW0_temp; - RW_[1] = RW1_temp; - RW_[2] = RW2_temp; - RW_[3] = RW3_temp; - } else if (number_of_RW == 3) { - RWModel RW0_temp(step_width, angular_velocity_init_0, inertia_0, angular_velocity_upperlimit_init_0, angular_velocity_lowerlimit_init_0, - motor_drive_init_0, angular_accelaration_init_0); - RWModel RW1_temp(step_width, angular_velocity_init_1, inertia_1, angular_velocity_upperlimit_init_1, angular_velocity_lowerlimit_init_1, - motor_drive_init_1, angular_accelaration_init_1); - RWModel RW2_temp(step_width, angular_velocity_init_2, inertia_2, angular_velocity_upperlimit_init_2, angular_velocity_lowerlimit_init_2, - motor_drive_init_2, angular_accelaration_init_2); - RW_[0] = RW0_temp; - RW_[1] = RW1_temp; - RW_[2] = RW2_temp; - } - torque_transition_ = torque_transition; -} -Vector<3> RWModule::GetTorque() { - Vector<4> torque_temp; - for (int i = 0; i < 4; i++) { - torque_temp[i] = RW_[i].GetTorque(); - } - return torque_transition_ * torque_temp; -} -void RWModule::SetTorque(double angular_accelaration, int module_number) { RW_[module_number].SetTorque(angular_accelaration); } -void RWModule::SetLimits(double angular_velocity_upperlimit, double angular_velocity_lowerlimit, int module_number) { - RW_[module_number].SetLimits(angular_velocity_upperlimit, angular_velocity_lowerlimit); -} -void RWModule::SetDrive(bool on, int module_number) { RW_[module_number].SetDrive(on); } -string RWModule::WriteLogHeader(void) { - string str_tmp = ""; - - str_tmp += WriteVector("RWtorque", "b", "Nm", 3); - for (int i = 0; i < 4; i++) { - str_tmp += RW_[i].WriteLogHeader(); - } - - return str_tmp; -} - -string RWModule::WriteLogValue(void) { - string str_tmp = ""; - - str_tmp += WriteVector(RWtorque_b_); - for (int i = 0; i < 4; i++) { - str_tmp += RW_[i].WriteLogValue(); - } - - return str_tmp; -} diff --git a/src/Component/AOCS/RWModule.h b/src/Component/AOCS/RWModule.h deleted file mode 100644 index 6f460c78d..000000000 --- a/src/Component/AOCS/RWModule.h +++ /dev/null @@ -1,36 +0,0 @@ -/* - * @file RWModule.h - * @brief Class to combine four reaction wheels - * @note We recommend not to use this class. Users can make multiple RW by making multiple instances of RWModel. TODO: Delete this class. - */ - -#include - -#include -#include - -#include "RWModel.h" - -class RWModule { - private: - RWModel RW_[4]; - Matrix<3, 4> torque_transition_; // トルク変換行列 - Vector<3> RWtorque_b_; // 出したトルク(ログ用) - public: - RWModule(); - RWModule(double step_width, double angular_velocity_init_0, double inertia_0, double angular_velocity_upperlimit_init_0, - double angular_velocity_lowerlimit_init_0, bool motor_drive_init_0, double angular_accelaration_init_0, double angular_velocity_init_1, - double inertia_1, double angular_velocity_upperlimit_init_1, double angular_velocity_lowerlimit_init_1, bool motor_drive_init_1, - double angular_accelaration_init_1, double angular_velocity_init_2, double inertia_2, double angular_velocity_upperlimit_init_2, - double angular_velocity_lowerlimit_init_2, bool motor_drive_init_2, double angular_accelaration_init_2, double angular_velocity_init_3, - double inertia_3, double angular_velocity_upperlimit_init_3, double angular_velocity_lowerlimit_init_3, bool motor_drive_init_3, - double angular_accelaration_init_3, int number_of_RW, libra::Matrix<3, 4> torque_transition); - libra::Vector<3> GetTorque(); // トルク発生 - void SetTorque(double angular_accelaration, - int module_number); // 必要な角加速度の指定(単位はrpm/s) - void SetLimits(double angular_velocity_upperlimit, double angular_velocity_lowerlimit, - int module_number); // UL/LLの設定(単位はrpm) - void SetDrive(bool on, int module_number); // 動作フラグの設定 - string WriteLogHeader(void); // ログofヘッダー - string WriteLogValue(void); // ログof値 -}; From 59e8d08d18414625b6f985e3c3bb86263855d5aa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:46:47 +0100 Subject: [PATCH 0007/1086] Delete UWBSensor --- src/Component/AOCS/InitUwbSensor.cpp | 26 ----- src/Component/AOCS/InitUwbSensor.hpp | 14 --- src/Component/AOCS/UWBSensor.cpp | 71 ----------- src/Component/AOCS/UWBSensor.h | 72 ------------ src/Component/CMakeLists.txt | 3 - src/Component/Logic/UWBEstimator.cpp | 169 --------------------------- src/Component/Logic/UWBEstimator.h | 63 ---------- 7 files changed, 418 deletions(-) delete mode 100644 src/Component/AOCS/InitUwbSensor.cpp delete mode 100644 src/Component/AOCS/InitUwbSensor.hpp delete mode 100644 src/Component/AOCS/UWBSensor.cpp delete mode 100644 src/Component/AOCS/UWBSensor.h delete mode 100644 src/Component/Logic/UWBEstimator.cpp delete mode 100644 src/Component/Logic/UWBEstimator.h diff --git a/src/Component/AOCS/InitUwbSensor.cpp b/src/Component/AOCS/InitUwbSensor.cpp deleted file mode 100644 index a07ea0b01..000000000 --- a/src/Component/AOCS/InitUwbSensor.cpp +++ /dev/null @@ -1,26 +0,0 @@ -/** - * @file InitUwbSensor.cpp - * @brief Initialize functions for UWB distance sensor - */ -#include "InitUwbSensor.hpp" - -#include "Interface/InitInput/IniAccess.h" - -UWBSensor InitUWBSensor(int sensor_id) { - IniAccess conf("data/ini/component/UWBSensor.ini"); - std::string section = "UWB" + std::to_string(sensor_id); - const char* csection = section.c_str(); - - Vector<3> pos; - conf.ReadVector(csection, "pos", pos); - Vector<3> dir; - conf.ReadVector(csection, "dir", dir); - Vector<3> axis; - conf.ReadVector(csection, "axis", axis); - - normalize(dir); - normalize(axis); - UWBSensor uwb(sensor_id, pos, dir, axis); - - return uwb; -} diff --git a/src/Component/AOCS/InitUwbSensor.hpp b/src/Component/AOCS/InitUwbSensor.hpp deleted file mode 100644 index 43bd5f30e..000000000 --- a/src/Component/AOCS/InitUwbSensor.hpp +++ /dev/null @@ -1,14 +0,0 @@ -/** - * @file InitUwbSensor.hpp - * @brief Initialize functions for UWB distance sensor - */ -#pragma once - -#include - -/** - * @fn InitUWBSensor - * @brief Initialize functions for UWB distance sensor - * @param [in] sensor_id: Sensor ID - */ -UWBSensor InitUWBSensor(int sensor_id); diff --git a/src/Component/AOCS/UWBSensor.cpp b/src/Component/AOCS/UWBSensor.cpp deleted file mode 100644 index 50fe33f75..000000000 --- a/src/Component/AOCS/UWBSensor.cpp +++ /dev/null @@ -1,71 +0,0 @@ -/** - * @file UWBSensor.cpp - * @brief Class to emulate Ultra Wide Band distance sensor - * @note This class is not managed now. TODO: Consider to delete. - */ - -#include "UWBSensor.h" - -#include - -UWBSensor::UWBSensor(int sensor_id, Vector<3> pos_b_, Vector<3> dir_b_, Vector<3> axis_b_) - : sensor_id(sensor_id), pos_b(pos_b_), dir_b(dir_b_), axis_b(axis_b_), measure_nr(0, 1, sensor_id) {} - -UWBSensor::~UWBSensor() {} - -int UWBSensor::IsVisible(UWBSensor& other) { - UWBSensor& o = other; - // チェーサーUWBからターゲットUWBへの相対位置ベクトル(慣性座標系) - Vector<3> rel_pos = LocationTo(other); - - Vector<3> dir_i = q_b2i.frame_conv(dir_b); - Vector<3> o_dir_i = o.q_b2i.frame_conv(o.dir_b); - - // UWB方向ベクトル間の内積(cos) - double dot_uwbs = dot(dir_i, o_dir_i); - - // UWB間相対位置ベクトルと受信側UWB方向ベクトル間の内積 - double dot_sigdir = dot(rel_pos, dir_i); - if (dot_uwbs > 0 || dot_sigdir < 0) { - // UWBのアンテナが非可視の位置関係にある - return 0; - } - - double theta = angle(q_b2i.frame_conv(axis_b), rel_pos); - double o_theta = angle(o.q_b2i.frame_conv(o.axis_b), rel_pos); - - double propagate_loss = -20 * log10(4 * libra::pi * fc * norm(rel_pos) / c); - double received_gain = Pt + propagate_loss + CalcAntennaGain(theta) + o.CalcAntennaGain(o_theta); - - if (received_gain > Plimit) return 1; - - return 0; -} - -Vector<3> UWBSensor::LocationTo(UWBSensor& other) { - UWBSensor& o = other; - // チェーサーUWBからターゲットUWBへの相対位置ベクトル(慣性座標系) - Vector<3> rel_pos = o.ref_pos_i - ref_pos_i - q_b2i.frame_conv(pos_b) + o.q_b2i.frame_conv(o.pos_b); - return rel_pos; -} - -double UWBSensor::MeasureDistanceTo(UWBSensor& other) { - auto rel_pos = LocationTo(other); - double distance = norm(rel_pos); - double noise = measure_nr * CalcDeviation(distance); - return distance + noise; -} - -void UWBSensor::SetParameters(Vector<3> pos_i, Quaternion q_i2b) { - ref_pos_i = pos_i; - q_b2i = q_i2b.conjugate(); -} - -double UWBSensor::CalcAntennaGain(double theta) { return 2.15 + 20 * log10(cos(libra::pi_2 * cos(theta)) / sin(theta)); } - -double UWBSensor::CalcDeviation(double distance) { - if (distance < 200 && distance >= 150) return 0.07; - if (distance < 150 && distance >= 100) return 0.05; - if (distance < 100) return 0.03; - return 0.1; -} diff --git a/src/Component/AOCS/UWBSensor.h b/src/Component/AOCS/UWBSensor.h deleted file mode 100644 index 4963095a0..000000000 --- a/src/Component/AOCS/UWBSensor.h +++ /dev/null @@ -1,72 +0,0 @@ -/** - * @file UWBSensor.h - * @brief Class to emulate Ultra Wide Band distance sensor - * @note This class is not managed now. TODO: Consider to delete. - */ - -#pragma once -#include -#include -#include -using libra::NormalRand; -using libra::Quaternion; -using libra::Vector; - -#include - -class UWBSensor { - public: - UWBSensor(int sensor_id, Vector<3> pos_b_, Vector<3> dir_b_, Vector<3> axis_b_); - ~UWBSensor(); - - // 対向UWBの電波送受信レベルが十分高ければ1を、受信できない状況では0を返す - // otherはターゲット側のUWBセンサーとする - int IsVisible(UWBSensor& other); - - Vector<3> LocationTo(UWBSensor& other); - - double MeasureDistanceTo(UWBSensor& other); - - // pos_i: 慣性系における宇宙機の位置ベクトル, q_i2b: 宇宙機のクオータニオン - void SetParameters(Vector<3> pos_i, Quaternion q_i2b); - - inline Vector<3> GetPos_b() { return pos_b; } - - private: - // 光速 [m/s] - static const int c = 299792458; - - // 受信限界ゲイン [dBm] - static const int Plimit = -105; - - const int sensor_id; - - // 機体座標でのUWBセンサーの位置ベクトル - Vector<3> pos_b; - - // UWB平面の法線ベクトル - Vector<3> dir_b; - - // DPアンテナの軸方向 - Vector<3> axis_b; - - // 取り付けている宇宙機の慣性座標での位置 - Vector<3> ref_pos_i; - - // 慣性座標から取り付けている宇宙機の機体座標へのクオータニオン - Quaternion q_b2i; - - // 送信電力[dBm] - double Pt = 9.3; - - // 中心周波数 [Hz] - double fc = 3993.6e6; - // 測距の観測ノイズ源 - NormalRand measure_nr; - - // theta方向のアンテナゲインを計算する - double CalcAntennaGain(double theta); - - // 測距ノイズの偏差[m](距離に依存する)を返す - double CalcDeviation(double distance); -}; diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 25ace7726..3b8e7f7a2 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -26,8 +26,6 @@ add_library(${PROJECT_NAME} STATIC AOCS/InitStt.cpp AOCS/SunSensor.cpp AOCS/InitSunSensor.cpp - AOCS/UWBSensor.cpp - AOCS/InitUwbSensor.cpp AOCS/GNSSReceiver.cpp AOCS/InitGnssReceiver.cpp @@ -47,7 +45,6 @@ add_library(${PROJECT_NAME} STATIC Logic/LPF.cpp Logic/RVDController.cpp - Logic/UWBEstimator.cpp Mission/Telescope/Telescope.cpp Mission/Telescope/InitTelescope.cpp diff --git a/src/Component/Logic/UWBEstimator.cpp b/src/Component/Logic/UWBEstimator.cpp deleted file mode 100644 index 953d48ed2..000000000 --- a/src/Component/Logic/UWBEstimator.cpp +++ /dev/null @@ -1,169 +0,0 @@ -#include "UWBEstimator.h" - -#include "../AOCS/UWBSensor.h" - -UWBEstimator::UWBEstimator(double dt, double Mt, double Mc, uwbvec uwb_t, uwbvec uwb_c) { - this->sigma_Q_tf = 0.001; - this->sigma_Q_cf = 0.001; - this->dt = dt; - this->Mc = Mc; - this->Mt = Mt; - this->uwb_t = uwb_t; - this->uwb_c = uwb_c; - - fill_up(P, 0.0); - fill_up(Q, 0.0); - fill_up(R, 0.0); - fill_up(H, 0.0); - fill_up(K, 0.0); - fill_up(M, 0.0); - fill_up(A, 0.0); - fill_up(B, 0.0); - fill_up(lastP, 0.0); - // Matrix<6, 6> A(0), B(0); - for (auto i = 0; i < 3; i++) { - A(i, i + 3) = 1; - B(i + 3, i) = 1 / Mt; - B(i + 3, i + 3) = -1 / Mc; - P(i, i) = 100; - P(i + 3, i + 3) = 3; - Q(i, i) = sigma_Q_tf * sigma_Q_tf; - Q(i + 3, i + 3) = sigma_Q_cf * sigma_Q_cf; - } - SetR(Vector<12>(1)); - Phi = libra::eye<6>() + dt * A; - Gamma = dt * B; - x *= 0; - hx *= 0; - Fcontrol_i *= 0; - lastObservation *= 0; -} - -UWBEstimator::~UWBEstimator() {} - -void UWBEstimator::Update(Vector<12> visibility, Vector<12> measurement) { - lastObservation = measurement; - lastP = P; - SetR(visibility); - SetH(); - M = Phi * P * transpose(Phi) + Gamma * Q * transpose(Gamma); - Matrix<12, 12> inv; - try { - inv = invert(H * M * transpose(H) + R); - } catch (...) { - fill_up(inv, 0.0); - std::cout << "singular!!\r\n"; - } - - K = M * transpose(H) * inv; - auto t3 = measurement - hx; - auto t4 = K * (t3); - x = x + t4; - // Joseph Form https://wolfweb.unr.edu/~fadali/EE782/DiscreteKF.pdf - auto temp = libra::eye<6>() - K * H; - P = temp * M * transpose(temp) + K * R * transpose(K); -} - -void UWBEstimator::Propagate(Vector<3> Ft, Vector<3> Fc) { - lastP = P; - for (auto i = 0; i < 3; i++) { - Fcontrol_i[i] = Ft[i]; - Fcontrol_i[i + 3] = Fc[i]; - } - x = Phi * x + Gamma * Fcontrol_i; - P = Phi * P * transpose(Phi) + Gamma * Q * transpose(Gamma); -} - -Vector<3> UWBEstimator::GetRelativePosition() const { - Vector<3> Le; - for (auto i = 0; i < 3; i++) Le[i] = x[i]; - return Le; -} - -Vector<3> UWBEstimator::GetRelativeVelocity() const { - Vector<3> Le_dot; - for (auto i = 0; i < 3; i++) Le_dot[i] = x[i + 3]; - return Le_dot; -} - -void UWBEstimator::SetQuaternion(Quaternion q_t_i2b, Quaternion q_c_i2b) { - q_t = q_t_i2b; - q_c = q_c_i2b; -} - -void UWBEstimator::SetX(Vector<6> x_new) { x = x_new; } - -bool UWBEstimator::IsConverged() { - auto Pdiff = P - lastP; - bool isconverged = true; - for (size_t i = 0; i < Pdiff.row(); i++) { - // 最初は1mで捕捉できてれば十分 - isconverged &= std::abs(Pdiff[i][i]) < 1e-2; - } - return isconverged; -} - -std::string UWBEstimator::GetLogHeader() const { - std::string str_tmp = ""; - str_tmp += WriteVector("RelPosEst", "i", "m", 3); - str_tmp += WriteVector("RelVelEst", "i", "m/s", 3); - str_tmp += WriteVector("UWBObs", "i", "m", 12); - str_tmp += WriteVector("Fcontrol", "i", "N", 6); - return str_tmp; -} - -std::string UWBEstimator::GetLogValue() const { - std::string str_tmp = ""; - str_tmp += WriteVector(x); - str_tmp += WriteVector(lastObservation); - str_tmp += WriteVector(Fcontrol_i); - return str_tmp; -} - -Vector<3> UWBEstimator::distanceVector(Vector<3> L, Quaternion qt_i2b, Quaternion qc_i2b, Vector<3> post_b, Vector<3> posc_b) { - return L + qt_i2b.frame_conv_inv(post_b) - qc_i2b.frame_conv_inv(posc_b); -} - -void UWBEstimator::SetR(Vector<12> visibility) { - auto dist_e = norm(GetRelativePosition()); - double sigma_R = CalcDeviation(dist_e); - for (auto i = 0; i < 12; i++) { - R[i][i] = visibility[i] ? sigma_R * sigma_R : Rinf; - } -} - -void UWBEstimator::SetH() { - for (auto i = 0; i < 3; i++) { - auto uwbc = uwb_c[i]; - for (auto j = 0; j < 4; j++) { - auto uwbt = uwb_t[j]; - auto Le = GetRelativePosition(); - auto relpos = distanceVector(Le, q_t, q_c, uwbt->GetPos_b(), uwbc->GetPos_b()); - auto relposnorm = norm(relpos); - hx[i * 4 + j] = relposnorm; - auto diffs = 1 / relposnorm * relpos; - for (auto k = 0; k < 3; k++) { - H[i * 4 + j][k] = diffs[k]; - } - } - } -} - -double UWBEstimator::CalcDeviation(double distance) { - double uwb_error = 0.1; - if (distance < 200 && distance >= 150) - uwb_error = 0.07; - else if (distance < 150 && distance >= 100) - uwb_error = 0.05; - else if (distance < 100) - uwb_error = 0.03; - else - uwb_error = 0.1; - - // STT誤差を考慮すると、観測ノイズの偏差は増加させる必要あり - // 200mで100が良かった 比例と仮定 - // いまいち根拠薄いが😩 - double stt_error_fac = 100 * (distance) / 200.0 + 1; - - return uwb_error * stt_error_fac; -} diff --git a/src/Component/Logic/UWBEstimator.h b/src/Component/Logic/UWBEstimator.h deleted file mode 100644 index 95b050ef9..000000000 --- a/src/Component/Logic/UWBEstimator.h +++ /dev/null @@ -1,63 +0,0 @@ -#pragma once - -#include -#include -#include -#include -using libra::Matrix; -using libra::Quaternion; -using libra::Vector; - -#include - -class UWBSensor; -using uwbvec = std::vector; - -class UWBEstimator : public ILoggable { - public: - UWBEstimator(double dt, double Mt, double Mc, uwbvec uwb_t, uwbvec uwb_c); - ~UWBEstimator(); - - void Update(Vector<12> visibility, Vector<12> measurement); - - // 伝播のメソッド - // Ft: ターゲットの制御並進力, Fc: チェイサーの制御並進力 - void Propagate(Vector<3> Ft, Vector<3> Fc); - - Vector<3> GetRelativePosition() const; - Vector<3> GetRelativeVelocity() const; - Quaternion GetRelativeAttitude() const; - - void SetQuaternion(Quaternion q_t_i2b, Quaternion q_c_i2b); - void SetX(Vector<6> x_new); - bool IsConverged(); - - std::string GetLogHeader() const; - std::string GetLogValue() const; - - private: - double Rinf = 1000000; - Matrix<12, 6> H; - Matrix<6, 12> K; - Matrix<6, 6> M; - Matrix<6, 6> P, Q, lastP; - Matrix<12, 12> R; - Matrix<6, 6> A, B; - Matrix<6, 6> Gamma, Phi; - Vector<6> x, Fcontrol_i; - Vector<12> hx; - Vector<12> lastObservation; - // Vector<3> Le, Ve; // 相対位置・速度ベクトルの推定値 - double dt; - double sigma_Q_tf, sigma_Q_cf; - double Mc, Mt; - uwbvec uwb_t, uwb_c; - Quaternion q_t, q_c; // i2b - - Vector<3> distanceVector(Vector<3> L, Quaternion qt_i2b, Quaternion qc_i2b, Vector<3> post_b, Vector<3> posc_b); - - void SetR(Vector<12> visibility); - void SetH(); - - double CalcDeviation(double distance); -}; From 4be9acd9e6b8a5750a63ecaa85f3f53dbde0057d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:49:19 +0100 Subject: [PATCH 0008/1086] Delete LPF --- src/Component/CMakeLists.txt | 1 - src/Component/Logic/LPF.cpp | 42 ------------------------------------ src/Component/Logic/LPF.h | 17 --------------- 3 files changed, 60 deletions(-) delete mode 100644 src/Component/Logic/LPF.cpp delete mode 100644 src/Component/Logic/LPF.h diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 3b8e7f7a2..8273cbb63 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -43,7 +43,6 @@ add_library(${PROJECT_NAME} STATIC IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp - Logic/LPF.cpp Logic/RVDController.cpp Mission/Telescope/Telescope.cpp diff --git a/src/Component/Logic/LPF.cpp b/src/Component/Logic/LPF.cpp deleted file mode 100644 index 773da3b2e..000000000 --- a/src/Component/Logic/LPF.cpp +++ /dev/null @@ -1,42 +0,0 @@ -#include "LPF.h" - -#include - -LPF::LPF(double omega_c, double sampling_t) { - using std::pow; - - double gamma = 0.5 * omega_c * sampling_t; - double gamma_2 = pow(gamma, 2.0); - double coef = 1.0 / pow(1 + gamma, 2.0); - - // フィルタ係数初期化 - a_[0] = 0.0; // 使用しない。 - a_[1] = coef * 2.0 * (gamma_2 - 1.0); - a_[2] = coef * pow(1.0 - gamma, 2.0); - - b_[0] = coef * gamma_2; - b_[1] = 2.0 * b_[0]; - b_[2] = b_[0]; - - // 入出力記憶の初期化(ここではすべて0.0とする) - for (int i = 0; i < 3; ++i) { - y_[i] = u_[i] = 0.0; - } -} - -double LPF::operator()(double u) { - // 入力バッファシフト - u_[2] = u_[1]; - u_[1] = u_[0]; - u_[0] = u; - // 出力バッファシフト - y_[2] = y_[1]; - y_[1] = y_[0]; - - y_[0] = b_[0] * u_[0]; - for (int i = 1; i < 3; ++i) { - y_[0] += -a_[i] * y_[i] + b_[i] * u_[i]; - } - - return y_[0]; -} diff --git a/src/Component/Logic/LPF.h b/src/Component/Logic/LPF.h deleted file mode 100644 index 05d4a3edc..000000000 --- a/src/Component/Logic/LPF.h +++ /dev/null @@ -1,17 +0,0 @@ -#ifndef LPF_H_ -#define LPF_H_ - -class LPF { - public: - LPF(double omega_c, double sampling_t); - double operator()(double u); - - private: - double y_[3]; - double u_[3]; - - double a_[3]; - double b_[3]; -}; - -#endif // LPF_H_ From d1fd42fe61a19853bdcf3ebedeb8fdc769c9ace3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:50:12 +0100 Subject: [PATCH 0009/1086] Delete RVDController --- src/Component/CMakeLists.txt | 2 - src/Component/Logic/RVDController.cpp | 103 -------------------------- src/Component/Logic/RVDController.h | 64 ---------------- 3 files changed, 169 deletions(-) delete mode 100644 src/Component/Logic/RVDController.cpp delete mode 100644 src/Component/Logic/RVDController.h diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 8273cbb63..0aa8932d2 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -43,8 +43,6 @@ add_library(${PROJECT_NAME} STATIC IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp - Logic/RVDController.cpp - Mission/Telescope/Telescope.cpp Mission/Telescope/InitTelescope.cpp diff --git a/src/Component/Logic/RVDController.cpp b/src/Component/Logic/RVDController.cpp deleted file mode 100644 index f6d6d04ec..000000000 --- a/src/Component/Logic/RVDController.cpp +++ /dev/null @@ -1,103 +0,0 @@ -#include "RVDController.h" - -RVDController::RVDController(double dt) : relPosCtrl(dt), relAttCtrl(dt), relVelCtrl(dt) { - relPosCtrl.SetGains(0.8, 20.0, 0.00); - relVelCtrl.SetGains(100, 0.0, 0.00); - relAttCtrl.SetGains(3.5, 13.0, 0); - thrust_b_ *= 0; - torque_ *= 0; -} - -RVDController::~RVDController() {} - -void RVDController::SetTargetRelPosition(Vector<3> relPos_i) { tar_relpos_i = relPos_i; } - -void RVDController::SetTargetRelVelocity(Vector<3> relVel_i) { tar_relvel_i = relVel_i; } - -void RVDController::SetTargetRelAttitude(Quaternion q12) { tar_q_i2b = q12; } - -void RVDController::SetPositionGain(double p, double d, double i) { relPosCtrl.SetGains(p, d, i); } - -Vector<2> RVDController::CalcCurrent() { - Vector<2> currents; - currents[0] = 5; - currents[1] = 5; - return currents; -} - -Vector<6> RVDController::CalcThrust(Vector<3> relpos_now_i, Quaternion q_i2b) { - auto input_i = relPosCtrl.CalcOutput(relpos_now_i - tar_relpos_i); - auto input_b = q_i2b.frame_conv(input_i); - auto res = CalcThrustEach(input_b); - return res; -} - -Vector<6> RVDController::CalcThrust(Vector<3> relpos_now_i, Vector<3> relvel_now_i, Quaternion q_i2b) { - auto input_i = relPosCtrl.CalcOutput(relpos_now_i - tar_relpos_i, relvel_now_i); - auto input_b = q_i2b.frame_conv(input_i); - auto res = CalcThrustEach(input_b); - return res; -} - -Vector<6> RVDController::CalcThrustVeloc(Vector<3> relvel_now_i, Quaternion q_i2b) { - auto input_i = relVelCtrl.CalcOutput(relvel_now_i - tar_relvel_i); - auto input_b = q_i2b.frame_conv(input_i); - auto res = CalcThrustEach(input_b); - return res; -} - -Vector<3> RVDController::CalcRW(Quaternion q_ib_now) { - Quaternion q_b2tar = (q_ib_now.conjugate()) * tar_q_i2b; - double angle = acos_tolerant(q_b2tar[3]); - Vector<3> trq_dir(0); - trq_dir[0] = q_b2tar[0]; - trq_dir[1] = q_b2tar[1]; - trq_dir[2] = q_b2tar[2]; - normalize(trq_dir); - auto pdiff = angle * trq_dir; - - auto res = relAttCtrl.CalcOutput(pdiff); - - return res; -} - -std::string RVDController::GetLogHeader() const { - std::string str_tmp = ""; - str_tmp += WriteVector("thrust", "b", "N", 3); - str_tmp += WriteVector("torque", "b", "Nm", 3); - return str_tmp; -} - -std::string RVDController::GetLogValue() const { - std::string str_tmp = ""; - str_tmp += WriteVector(thrust_b_); - str_tmp += WriteVector(torque_); - return str_tmp; -} - -double RVDController::acos_tolerant(double x) { - x = (x > 1) ? 1 : x; - x = (x < -1) ? -1 : x; - return acos(x); -} - -Vector<6> RVDController::CalcThrustEach(Vector<3> thrusts) { - const double sf_x = 1; - - Vector<6> results(0); - int idx[3]; - idx[0] = thrusts[0] > 0 ? MX : PX; - idx[1] = thrusts[1] > 0 ? MY : PY; - idx[2] = thrusts[2] > 0 ? MZ : PZ; - - for (int i = 0; i < 3; i++) { - int sign = thrusts[i] > 0 ? 1 : -1; - double thrust = std::abs(thrusts[i]); - thrust *= sf_x; - if (thrust > 1) thrust = 1; - results(idx[i]) = thrust; - - thrust_b_[i] = sign * thrust * 50e-3; - } - return results; -} diff --git a/src/Component/Logic/RVDController.h b/src/Component/Logic/RVDController.h deleted file mode 100644 index 00cbecea1..000000000 --- a/src/Component/Logic/RVDController.h +++ /dev/null @@ -1,64 +0,0 @@ -#pragma once - -#include -#include - -#include - -#include "PIDController.h" - -const int MX = 0; -const int PX = 1; -const int MY = 2; -const int PY = 3; -const int MZ = 4; -const int PZ = 5; - -class RVDController : public ILoggable { - public: - RVDController(double dt); - ~RVDController(); - - void SetTargetRelPosition(Vector<3> relPos_i); - void SetTargetRelVelocity(Vector<3> relVel_i); - void SetTargetRelAttitude(Quaternion q12); - - void SetPositionGain(double p, double d, double i); - - Vector<2> CalcCurrent(); // FIXME: Do we need this? - - // 3軸±方向に必要なスラスト - Vector<6> CalcThrust(Vector<3> relpos_now_i, Quaternion q_i2b); - Vector<6> CalcThrust(Vector<3> relpos_now_i, Vector<3> relvel_now_i, Quaternion q_i2b); - Vector<6> CalcThrustVeloc(Vector<3> relvel_now_i, Quaternion q_i2b); - - // 3軸方向に必要なトルク - Vector<3> CalcRW(Quaternion q_ib_now); - - inline Vector<3> GetForce_b() { return thrust_b_; } - inline Vector<3> GetTorque() { return torque_; } - inline void ClearForce() { thrust_b_ *= 0; } - - virtual std::string GetLogHeader() const; - virtual std::string GetLogValue() const; - - private: - double acos_tolerant(double x); - Vector<3> thrust_b_; - Vector<3> torque_; - - PIDController<3> relPosCtrl; - PIDController<3> relAttCtrl; - PIDController<3> relVelCtrl; - - // 目標相対位置(母機から見た子機の慣性系座標) - Vector<3> tar_relpos_i; - - // 目標相対位置(母機から見た子機の慣性系座標) - Vector<3> tar_relvel_i; - - // 目標クオータニオン - Quaternion tar_q_i2b; - - Vector<6> CalcThrustEach(Vector<3> thrusts); -}; From f18f6c7af24fa719fe03d82f0938c3ea30af66d4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:52:07 +0100 Subject: [PATCH 0010/1086] Delete Logic directory --- src/Component/Logic/PIDController.h | 76 ----------------------------- 1 file changed, 76 deletions(-) delete mode 100644 src/Component/Logic/PIDController.h diff --git a/src/Component/Logic/PIDController.h b/src/Component/Logic/PIDController.h deleted file mode 100644 index f0995f7d3..000000000 --- a/src/Component/Logic/PIDController.h +++ /dev/null @@ -1,76 +0,0 @@ -#pragma once -#include -using libra::Vector; - -template -class PIDController { - public: - PIDController(double dt); - ~PIDController(); - - // PID計算をして出力(制御トルクなど)を計算 - Vector CalcOutput(Vector p_error); - - // PID計算をして出力(制御トルクなど)を計算 - Vector CalcOutput(Vector p_error, Vector current_d); - - // ゲインを設定 - void SetGains(double p, double d, double i); - - private: - bool isFirst = true; - double pGain = 0; - double dGain = 0; - double iGain = 0; - double dt = 1; - - // 1ステップ前の状態量 - Vector last_p; - - // 積分項 - Vector term_i; -}; - -template -PIDController::PIDController(double dt_) { - dt = dt_; - last_p = Vector(0); - term_i = Vector(0); -} - -template -PIDController::~PIDController() {} - -template -Vector PIDController::CalcOutput(Vector p_error) { - if (isFirst) { - isFirst = false; - last_p = p_error; - } - Vector dvec = (p_error - last_p); - dvec /= dt; - last_p = p_error; - - return CalcOutput(p_error, dvec); -} - -template -inline Vector PIDController::CalcOutput(Vector p_error, Vector current_d) { - auto dvec = current_d; - dvec *= 1; - - term_i += dt * p_error; - Vector ivec = term_i; - - Vector pvec = p_error; - - Vector output = pGain * pvec + dGain * dvec + iGain * ivec; - return output; -} - -template -void PIDController::SetGains(double p, double d, double i) { - pGain = p; - dGain = d; - iGain = i; -} From d9f673f99459903e940366a196f332c50a8861b7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 09:54:27 +0100 Subject: [PATCH 0011/1086] Delete COSMOS related codes --- src/Interface/HilsInOut/COSMOSWrapper.cpp | 70 -------------------- src/Interface/HilsInOut/COSMOSWrapper.h | 75 --------------------- src/Interface/HilsInOut/COSMOS_TCP_IF.cpp | 80 ----------------------- src/Interface/HilsInOut/COSMOS_TCP_IF.h | 74 --------------------- 4 files changed, 299 deletions(-) delete mode 100644 src/Interface/HilsInOut/COSMOSWrapper.cpp delete mode 100644 src/Interface/HilsInOut/COSMOSWrapper.h delete mode 100644 src/Interface/HilsInOut/COSMOS_TCP_IF.cpp delete mode 100644 src/Interface/HilsInOut/COSMOS_TCP_IF.h diff --git a/src/Interface/HilsInOut/COSMOSWrapper.cpp b/src/Interface/HilsInOut/COSMOSWrapper.cpp deleted file mode 100644 index 802d84cb2..000000000 --- a/src/Interface/HilsInOut/COSMOSWrapper.cpp +++ /dev/null @@ -1,70 +0,0 @@ -/** - * @file COSMOSWrapper.cpp - * @brief Wrapper for COSMOS - * @details COSMOS (Currently, called OpenC3) : https://openc3.com/ - * @note This file is very old and recently not managed well... - */ - -#include "COSMOSWrapper.h" - -COSMOSWrapper::COSMOSWrapper(bool enable) : enable_(enable) { - // cosmos_tcp_if_ = new COSMOS_TCP_IF(); -} - -COSMOSWrapper::COSMOSWrapper() : enable_(false) {} - -COSMOSWrapper::COSMOSWrapper(unsigned short port_num, bool enable, char* server_ip) : COSMOS_TCP_IF(port_num, server_ip), enable_(enable) {} - -COSMOSWrapper::~COSMOSWrapper() {} - -void COSMOSWrapper::Initialize() { - if (!enable_) return; - - // Error messages are generated inside the Initialize function - int ret = COSMOS_TCP_IF::Initialize(); -} - -void COSMOSWrapper::Finalize() { COSMOS_TCP_IF::Finalize(); } - -bool COSMOSWrapper::Enable() const { return enable_; } - -// Wrapper of cmd function to send data from COSMOS to RDP -void COSMOSWrapper::Cmd(std::string cmd_str) { - if (!enable_) return; - - std::string expr = "cmd(\""; - expr += cmd_str; - expr += "\")"; - CosmosEval(expr); -} - -void COSMOSWrapper::CosmosEval(std::string expr) { - if (!enable_) return; - // Expected the Ruby side directly pass the string to eval function - COSMOS_TCP_IF::SendString(expr); -} - -void COSMOSWrapper::Cmd_RDP_SAT_CMD_EXTERNAL_TORQUE(uint8_t torque_frame, uint32_t duration_ms, float ext_torque_x, float ext_torque_y, - float ext_torque_z) { - if (!enable_) return; - - // cmd("SAT SAT_CMD_EXTERNAL_TORQUE with SYNC_HI 3162369199, SYNC_LO - // 3737844679, LEN 21, AP_ID 2, OP_CODE 1, TORQUE_FRAME 'BODY', SPARE 0, - // DURATION_MS 1000, EXT_TORQUE_X 0.1, EXT_TORQUE_Y 0, EXT_TORQUE_Z 0") - // std::string cmd_str = "SAT SAT_CMD_EXTERNAL_TORQUE with TORQUE_FRAME "; - std::string cmd_str = - "SAT SAT_CMD_EXTERNAL_TORQUE with SYNC_HI 3162369199, SYNC_LO " - "3737844679, LEN 21, AP_ID 2, OP_CODE 1, TORQUE_FRAME 'BODY', SPARE 0"; - - // cmd_str += std::to_string(torque_frame); - cmd_str += ", DURATION_MS "; - cmd_str += std::to_string(duration_ms); - cmd_str += ", EXT_TORQUE_X "; - cmd_str += std::to_string(ext_torque_x); - cmd_str += ", EXT_TORQUE_Y "; - cmd_str += std::to_string(ext_torque_y); - cmd_str += ", EXT_TORQUE_Z "; - cmd_str += std::to_string(ext_torque_z); - - Cmd(cmd_str); -} diff --git a/src/Interface/HilsInOut/COSMOSWrapper.h b/src/Interface/HilsInOut/COSMOSWrapper.h deleted file mode 100644 index 4c85f0c8e..000000000 --- a/src/Interface/HilsInOut/COSMOSWrapper.h +++ /dev/null @@ -1,75 +0,0 @@ -/** - * @file COSMOSWrapper.h - * @brief Wrapper for COSMOS - * @details COSMOS (Currently, called OpenC3) : https://openc3.com/ - * @note This file is very old and recently not managed well... - */ - -#pragma once -#include - -#include "COSMOS_TCP_IF.h" -/** - * @class COSMOSWrapper - * @brief Wrapper for COSMOS - */ -class COSMOSWrapper : private COSMOS_TCP_IF { - public: - /** - * @fn COSMOSWrapper - * @brief Constructor. - */ - COSMOSWrapper(bool enable); - /** - * @fn COSMOSWrapper - * @brief Constructor. - */ - COSMOSWrapper(unsigned short port_num, bool enable, char* server_ip); - /** - * @fn COSMOSWrapper - * @brief Default Constructor. When not in use - */ - COSMOSWrapper(); - /** - * @fn ~COSMOSWrapper - * @brief Destructor. - */ - ~COSMOSWrapper(); - - /** - * @fn Cmd - * @brief Wrapper of cmd function to send data from COSMOS to RDP - * @param [in] cmd_str: String of command - */ - void Cmd(std::string cmd_str); - /** - * @fn Cmd_RDP_SAT_CMD_EXTERNAL_TORQUE - * @brief Command to set external torque - */ - void Cmd_RDP_SAT_CMD_EXTERNAL_TORQUE(uint8_t torque_frame, uint32_t duration_ms, float ext_torque_x, float ext_torque_y, float ext_torque_z); - - /** - * @fn Initialize - * @brief Initialize the TCP connection with COSMOS - */ - void Initialize(); - /** - * @fn Finalize - * @brief Finalize the TCP connection with COSMOS - */ - void Finalize(); - /** - * @fn Enable - * @brief Return enable flag - */ - bool Enable() const; - - private: - /** - * @fn CosmosEval - * @brief Send string to COSMOS - */ - void CosmosEval(std::string expr); - - const bool enable_; //!< Enable flag -}; diff --git a/src/Interface/HilsInOut/COSMOS_TCP_IF.cpp b/src/Interface/HilsInOut/COSMOS_TCP_IF.cpp deleted file mode 100644 index 60b92917a..000000000 --- a/src/Interface/HilsInOut/COSMOS_TCP_IF.cpp +++ /dev/null @@ -1,80 +0,0 @@ -/** - * @file COSMOS_TCP_IF.cpp - * @brief TCP interface to communicate with COSMOS software - * @details Currently, this feature supports Windows Visual Studio only.(FIXME) - * @note This file is very old and recently not managed well... - */ - -#include "COSMOS_TCP_IF.h" - -// References for TCP communication (Written in Japanese) -// https://web.archive.org/web/20181106125907/http://www.geocities.jp/playtown1056/program/index.htm - -COSMOS_TCP_IF::COSMOS_TCP_IF() : kPortNum(COSMOS_TCP_PORT_DEFAULT) { is_connected_ = false; } - -COSMOS_TCP_IF::COSMOS_TCP_IF(unsigned short port_num, const char *server_ip) : kPortNum(port_num), kServerIP(server_ip) { is_connected_ = false; } - -COSMOS_TCP_IF::~COSMOS_TCP_IF() { - closesocket(sock_); // Not to forget - WSACleanup(); -} - -int COSMOS_TCP_IF::Initialize() { - int ret; - // Windows - WSADATA data; - - // Initialize winsock2 - ret = WSAStartup(MAKEWORD(2, 0), &data); - if (ret != 0) { - printf("WSAStartupに失敗しました。\n"); - return ret; - } - - // Setting socket - sock_ = socket(AF_INET, SOCK_STREAM, 0); - - // Setting server - server_.sin_family = AF_INET; - server_.sin_port = htons(10005); - - // Setting IP address of server as localhost address - const char *ip = kServerIP.c_str(); - server_.sin_addr.s_addr = inet_addr(ip); - if (server_.sin_addr.s_addr == 0xffffffff) { - struct hostent *host; - - // Get IP from name (named by DSN) - host = gethostbyname(ip); - if (host == NULL) { - return 1; - } - // Possible to get 32 bit IP from the host - server_.sin_addr.s_addr = *(unsigned int *)host->h_addr_list[0]; - } - - // Connect server - ret = connect(sock_, (struct sockaddr *)&server_, sizeof(server_)); - if (ret != 0) { - printf("COSMOSサーバーとの接続に失敗しました。\n"); - return ret; - } else { - // Success to connect - is_connected_ = true; - printf("COSMOSサーバーとの接続に成功しました\n"); - return 0; - } -} - -void COSMOS_TCP_IF::SendString(std::string str) { - if (!is_connected_) return; - - std::string ret = str + ENDOFMSG; - // Send string to COSMOS - send(sock_, ret.c_str(), ret.length(), 0); -} - -void COSMOS_TCP_IF::Finalize() { - closesocket(sock_); - is_connected_ = false; -} diff --git a/src/Interface/HilsInOut/COSMOS_TCP_IF.h b/src/Interface/HilsInOut/COSMOS_TCP_IF.h deleted file mode 100644 index 61ad90c85..000000000 --- a/src/Interface/HilsInOut/COSMOS_TCP_IF.h +++ /dev/null @@ -1,74 +0,0 @@ -/** - * @file COSMOS_TCP_IF.h - * @brief TCP interface to communicate with COSMOS software - * @details Currently, this feature supports Windows Visual Studio only.(FIXME) - * @note This file is very old and recently not managed well... - */ - -#pragma once -#ifndef _WINSOCK_DEPRECATED_NO_WARNINGS -#define _WINSOCK_DEPRECATED_NO_WARNINGS -#endif -#include -#include -#include -#include - -#include - -#define COSMOS_TCP_PORT_DEFAULT 10001 - -#define ENDOFMSG "\n" - -/** - * @class COSMOS_TCP_IF - * @brief TCP interface to communicate with COSMOS software - */ -class COSMOS_TCP_IF { - public: - /** - * @fn COSMOS_TCP_IF - * @brief Default Constructor. - */ - COSMOS_TCP_IF(); - /** - * @fn COSMOS_TCP_IF - * @brief Constructor - */ - COSMOS_TCP_IF(unsigned short port_num, const char* server_ip); - /** - * @fn ~COSMOS_TCP_IF - * @brief Destructor - */ - ~COSMOS_TCP_IF(); - - /** - * @fn Initialize - * @brief Open and initialize the TCP socket - */ - int Initialize(); - /** - * @fn Finalize - * @brief Close and finalize the TCP socket - */ - void Finalize(); - - protected: - /** - * @fn SendString - * @brief Send string to COSMOS - */ - void SendString(std::string str); - - private: - const unsigned short kPortNum; //!< Port Number - const std::string kServerIP; //!< IP address of the server - SOCKET sock_; //!< socket - // struct sockaddr_in srcAddr_; - // struct sockaddr_in dstAddr_; - struct sockaddr_in server_; //!< Server - - // int dstAddrSize_ = sizeof(dstAddr_); - int serverAddrSize = sizeof(server_); //!< Server address size - bool is_connected_; //!< Is connected -}; From 2bbc0b142d2e51ec146ff0bc9d85e6f235b4b3de Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 10:00:12 +0100 Subject: [PATCH 0012/1086] Delete TMTCInterface --- src/Component/CDH/TMTCInterface.cpp | 16 ---------------- src/Component/CDH/TMTCInterface.h | 23 ----------------------- 2 files changed, 39 deletions(-) delete mode 100644 src/Component/CDH/TMTCInterface.cpp delete mode 100644 src/Component/CDH/TMTCInterface.h diff --git a/src/Component/CDH/TMTCInterface.cpp b/src/Component/CDH/TMTCInterface.cpp deleted file mode 100644 index 12df540f1..000000000 --- a/src/Component/CDH/TMTCInterface.cpp +++ /dev/null @@ -1,16 +0,0 @@ -/* - * @file TMTCInterface.cpp - * @brief Class for telemetry command communication with SILS GSTOS IF - * @note TODO: Is this still needed? We can use normal serial communication port - */ - -#include "TMTCInterface.h" - -TMTCInterface::TMTCInterface(ClockGenerator* clock_gen, int port_id) : ComponentBase(100, clock_gen) { tmtc_ = gcnew TMTCDriver(port_id); } - -TMTCInterface::~TMTCInterface() {} - -void TMTCInterface::MainRoutine(int count) { - tmtc_->ReceiveCommand(); - tmtc_->SendTelemetryIfAny(); -} diff --git a/src/Component/CDH/TMTCInterface.h b/src/Component/CDH/TMTCInterface.h deleted file mode 100644 index 79b9f78b1..000000000 --- a/src/Component/CDH/TMTCInterface.h +++ /dev/null @@ -1,23 +0,0 @@ -/* - * @file TMTCInterface.h - * @brief Class for telemetry command communication with SILS GSTOS IF - * @note TODO: Is this still needed? We can use normal serial communication port - */ - -#pragma once -#include - -#include "..\..\Interface\SpacecraftInOut\TMTCDriver.h" -#include "..\Abstract\ComponentBase.h" - -class TMTCInterface : public ComponentBase { - public: - TMTCInterface(ClockGenerator* clock_gen, int port_id); - ~TMTCInterface(); - - protected: - virtual void MainRoutine(int count); - - private: - msclr::gcroot tmtc_; -}; From b0cad10b9b1b523028e6744fe26bd5aaa5c04284 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 10:03:31 +0100 Subject: [PATCH 0013/1086] Delete TMTCDriver --- src/Interface/SpacecraftInOut/CMakeLists.txt | 5 -- src/Interface/SpacecraftInOut/TMTCDriver.cpp | 63 -------------------- src/Interface/SpacecraftInOut/TMTCDriver.h | 32 ---------- 3 files changed, 100 deletions(-) delete mode 100644 src/Interface/SpacecraftInOut/TMTCDriver.cpp delete mode 100644 src/Interface/SpacecraftInOut/TMTCDriver.h diff --git a/src/Interface/SpacecraftInOut/CMakeLists.txt b/src/Interface/SpacecraftInOut/CMakeLists.txt index 85a15dfc3..ee6054885 100644 --- a/src/Interface/SpacecraftInOut/CMakeLists.txt +++ b/src/Interface/SpacecraftInOut/CMakeLists.txt @@ -7,11 +7,6 @@ add_library(${PROJECT_NAME} STATIC Ports/SCIPort.cpp Ports/I2CPort.cpp Utils/RingBuffer.cpp - -## C++/CLI related codes -# Utils/ITCTMChannel.h -# TMTCDriver.cpp -# TMTCDriver.h ) include(../../../common.cmake) diff --git a/src/Interface/SpacecraftInOut/TMTCDriver.cpp b/src/Interface/SpacecraftInOut/TMTCDriver.cpp deleted file mode 100644 index 0825655e6..000000000 --- a/src/Interface/SpacecraftInOut/TMTCDriver.cpp +++ /dev/null @@ -1,63 +0,0 @@ -/** - * @file TMTCDriver.cpp - * @brief Driver of TMTC - */ - -#include "TMTCDriver.h" - -typedef cli::array arr; - -TMTCDriver::TMTCDriver(int port_id) : kPortId(port_id) { Initialize(); } - -void TMTCDriver::Initialize() { - try { - ChannelFactory ^ pipeFactory = - gcnew ChannelFactory(gcnew NetNamedPipeBinding(), gcnew EndpointAddress("net.pipe://localhost/TMTC_SILS")); - tctm_if_ = pipeFactory->CreateChannel(); - tctm_if_->Cmd_to_SILS(); // Try to send - } catch (Exception ^) { - // Console::WriteLine("Failed to connect GSTOS interface..."); - tctm_if_ = nullptr; - return; - } - - Console::WriteLine("Successfully connected to GSTOS interface."); - SCIDriver::ConnectPort(kPortId); -} - -void TMTCDriver::ReceiveCommand() { - if (tctm_if_ == nullptr) return; - arr ^ cmdbuf; - try { - cmdbuf = tctm_if_->Cmd_to_SILS(); - } catch (Exception ^) { - // Never try communication only one fail (Fixme?) - tctm_if_ = nullptr; - return; - } - if (cmdbuf == nullptr) return; - - int cnt = cmdbuf->Length; - if (cnt < 0) return; - pin_ptr buf = &cmdbuf[0]; - SCIDriver::SendToSC(kPortId, (Byte*)buf, 0, cnt); -} - -void TMTCDriver::SendTelemetryIfAny() { - if (tctm_if_ == nullptr) return; - Byte buf[1024]; - int cnt = SCIDriver::ReceiveFromSC(kPortId, buf, 0, 1024); - if (cnt <= 0) return; - - arr ^ tlmbuf = gcnew arr(cnt); - for (int i = 0; i < cnt; i++) { - tlmbuf[i] = buf[i]; - } - - try { - tctm_if_->Tlm_to_GSTOS(tlmbuf); - } catch (Exception ^) { - tctm_if_ = nullptr; - return; - } -} \ No newline at end of file diff --git a/src/Interface/SpacecraftInOut/TMTCDriver.h b/src/Interface/SpacecraftInOut/TMTCDriver.h deleted file mode 100644 index acf168da0..000000000 --- a/src/Interface/SpacecraftInOut/TMTCDriver.h +++ /dev/null @@ -1,32 +0,0 @@ -/** - * @file TMTCDriver.h - * @brief Driver of TMTC - */ - -#pragma once -//#include "../../../stdafx.h" -#include "SCIDriver.h" -#include "Utils/ITCTMChannel.h" - -using namespace System; -using namespace System::ServiceModel; -using namespace System::ServiceModel::Channels; - -/** - * @class TMTCDriver - * @brief Driver of TMTC - * @details Execute the process communication with SILS_GSTOS_IF to send telemetry and receive command - * @details Managed class for IPC. You can use as a native class by using gcroot. - */ -ref class TMTCDriver { - public: - TMTCDriver(int port_id); - void ReceiveCommand(); - void SendTelemetryIfAny(); - - private: - ITCTMChannel ^ tctm_if_; - const unsigned char kPortId = 7; - - void Initialize(); -}; From f3c89ddf06b891d2254ea3db83f5fb048d6e446e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 10:05:18 +0100 Subject: [PATCH 0014/1086] Delete unused initialize files --- data/SampleSat/ini/component/EMDS.ini | 11 --- data/SampleSat/ini/component/UWBSensor.ini | 90 ---------------------- 2 files changed, 101 deletions(-) delete mode 100644 data/SampleSat/ini/component/EMDS.ini delete mode 100644 data/SampleSat/ini/component/UWBSensor.ini diff --git a/data/SampleSat/ini/component/EMDS.ini b/data/SampleSat/ini/component/EMDS.ini deleted file mode 100644 index 094c602c4..000000000 --- a/data/SampleSat/ini/component/EMDS.ini +++ /dev/null @@ -1,11 +0,0 @@ -[EMDS0] -//EMDSの配置ズレ -displacement(0) = 0.0 -displacement(1) = 1.25 -displacement(2) = 0.0 - -[EMDS1] -//EMDSの配置ズレ -displacement(0) = 0.0 -displacement(1) = 0.0 -displacement(2) = 0.15 \ No newline at end of file diff --git a/data/SampleSat/ini/component/UWBSensor.ini b/data/SampleSat/ini/component/UWBSensor.ini deleted file mode 100644 index 48cb82ba2..000000000 --- a/data/SampleSat/ini/component/UWBSensor.ini +++ /dev/null @@ -1,90 +0,0 @@ -[UWB1] -pos(0) = 1.25 -pos(1) = -1.25 -pos(2) = -5 - -dir(0) = 0 -dir(1) = 1 -dir(2) = 0 - -axis(0) = 0 -axis(1) = 0 -axis(2) = 1 - -[UWB2] -pos(0) = -1.25 -pos(1) = -1.25 -pos(2) = 5 - -dir(0) = 0 -dir(1) = 1 -dir(2) = 0 - -axis(0) = 0 -axis(1) = 0 -axis(2) = 1 - -[UWB3] -pos(0) = 1.25 -pos(1) = 1.25 -pos(2) = 5 - -dir(0) = 0 -dir(1) = 1 -dir(2) = 0 - -axis(0) = 0 -axis(1) = 0 -axis(2) = 1 - -[UWB4] -pos(0) = -1.25 -pos(1) = 1.25 -pos(2) = -5 - -dir(0) = 0 -dir(1) = 1 -dir(2) = 0 - -axis(0) = 0 -axis(1) = 0 -axis(2) = 1 - -[UWB5] -pos(0) = 0.1 -pos(1) = -0.05 -pos(2) = -0.15 - -dir(0) = 0 -dir(1) = 0 -dir(2) = 1 - -axis(0) = 1 -axis(1) = 0 -axis(2) = 0 - -[UWB6] -pos(0) = -0.1 -pos(1) = 0.05 -pos(2) = -0.15 - -dir(0) = 0 -dir(1) = 0 -dir(2) = 1 - -axis(0) = 1 -axis(1) = 0 -axis(2) = 0 - -[UWB7] -pos(0) = 0.1 -pos(1) = 0.05 -pos(2) = 0.15 - -dir(0) = 0 -dir(1) = 0 -dir(2) = 1 - -axis(0) = 1 -axis(1) = 0 -axis(2) = 0 From 9c961514280462a2e674aaa8c333d85b5ea5948e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 13:21:42 +0100 Subject: [PATCH 0015/1086] Modify time initialize --- data/SampleSat/ini/SampleSimBase.ini | 36 +++++++++---------- .../Global/InitGlobalEnvironment.cpp | 27 +++++++------- 2 files changed, 32 insertions(+), 31 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index 0af610828..8dd49911a 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -1,47 +1,47 @@ -[TIME] -// Simulation start date [UTC] -StartYMDHMS=2020/01/01 12:00:00.0 +[Time] +// Simulation start time [UTC] +simulation_start_time_utc = 2020/01/01 12:00:00.0 -// Simulation finish time [sec] -EndTimeSec=200 +// Simulation duration [sec] +simulation_duration_s = 200 // Simulation step time [sec] // Minimum time step for the entire simulation -StepTimeSec=0.1 +simulation_step_s = 0.1 // Attitude Update Period [sec] // Attitude is updated at the period specified here -AttitudeUpdateIntervalSec=0.1 // should be larger than StepTimeSec +attitude_update_period_s = 0.1 // should be larger than 'simulation_step_s' // Attitide Δt for Runge-Kutt method [sec] -// This must be smaller than "AttitudeUpdateIntervalSec" -AttitudeRKStepSec = 0.001 +// This must be smaller than 'attitude_update_period_s' +attitude_integral_step_s = 0.001 // Orbit Update Period [sec] // Orbit is updated at the period specified here -OrbitUpdateIntervalSec = 0.1 // should be larger than StepTimeSec +orbit_update_period_s = 0.1 // should be larger than 'simulation_step_s' // Orbit Δt for Runge-Kutta method [sec] -// This must be smaller than "OrbitUpdateIntervalSec" -OrbitRKStepSec = 0.1 +// This must be smaller than 'orbit_ppdate_period_s' +orbit_integral_step_s = 0.1 // Thermal Update Period [sec] // Thermal is updated at the period specified here -ThermalUpdateIntervalSec = 0.1 // should be larger than StepTimeSec +thermal_update_period_s = 0.1 // should be larger than 'simulation_step_s' // Thermal Δt for Runge-Kutta method [sec] -// This must be smaller than "ThermalUpdateIntervalSec" -ThermalRKStepSec = 0.1 +// This must be smaller than 'thermal_update_period_s' +thermal_integral_step_s = 0.1 // Component Update Period [sec] -CompoUpdateIntervalSec = 0.1 // should be larger than StepTimeSec +component_update_period_s = 0.1 // should be larger than 'simulation_step_s' // Log Output Period [sec] -LogOutPutIntervalSec = 0.1 // should be larger than StepTimeSec +log_output_period_s = 0.1 // should be larger than 'simulation_step_s' // Simulation speed // 0: as fast as possible, 1: real-time, >1: faster than real-time, <1: slower than real-time -SimulationSpeed = 0 +simulation_speed_setting = 0 [MC_EXECUTION] diff --git a/src/Environment/Global/InitGlobalEnvironment.cpp b/src/Environment/Global/InitGlobalEnvironment.cpp index ca1e926d0..54337c23e 100644 --- a/src/Environment/Global/InitGlobalEnvironment.cpp +++ b/src/Environment/Global/InitGlobalEnvironment.cpp @@ -16,26 +16,27 @@ SimTime* InitSimTime(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "TIME"; + const char* section = "Time"; // Parameters about entire simulation - double end_sec = ini_file.ReadDouble(section, "EndTimeSec"); - double step_sec = ini_file.ReadDouble(section, "StepTimeSec"); - std::string start_ymdhms = ini_file.ReadString(section, "StartYMDHMS"); - double sim_speed = ini_file.ReadDouble(section, "SimulationSpeed"); + std::string start_ymdhms = ini_file.ReadString(section, "simulation_start_time_utc"); + double end_sec = ini_file.ReadDouble(section, "simulation_duration_s"); + double step_sec = ini_file.ReadDouble(section, "simulation_step_s"); // Time step parameters for dynamics propagation - double attitude_update_interval_sec = ini_file.ReadDouble(section, "AttitudeUpdateIntervalSec"); - double attitude_rk_step_sec = ini_file.ReadDouble(section, "AttitudeRKStepSec"); - double orbit_update_interval_sec = ini_file.ReadDouble(section, "OrbitUpdateIntervalSec"); - double orbit_rk_step_sec = ini_file.ReadDouble(section, "OrbitRKStepSec"); - double thermal_update_interval_sec = ini_file.ReadDouble(section, "ThermalUpdateIntervalSec"); - double thermal_rk_step_sec = ini_file.ReadDouble(section, "ThermalRKStepSec"); + double attitude_update_interval_sec = ini_file.ReadDouble(section, "attitude_update_period_s"); + double attitude_rk_step_sec = ini_file.ReadDouble(section, "attitude_integral_step_s"); + double orbit_update_interval_sec = ini_file.ReadDouble(section, "orbit_update_period_s"); + double orbit_rk_step_sec = ini_file.ReadDouble(section, "orbit_integral_step_s"); + double thermal_update_interval_sec = ini_file.ReadDouble(section, "thermal_update_period_s"); + double thermal_rk_step_sec = ini_file.ReadDouble(section, "thermal_integral_step_s"); // Time step parameter for component propagation - double compo_propagate_step_sec = ini_file.ReadDouble(section, "CompoUpdateIntervalSec"); + double compo_propagate_step_sec = ini_file.ReadDouble(section, "component_update_period_s"); // Time step parameter for log output - double log_output_interval_sec = ini_file.ReadDouble(section, "LogOutPutIntervalSec"); + double log_output_interval_sec = ini_file.ReadDouble(section, "log_output_period_s"); + + double sim_speed = ini_file.ReadDouble(section, "simulation_speed_setting"); SimTime* simTime = new SimTime(end_sec, step_sec, attitude_update_interval_sec, attitude_rk_step_sec, orbit_update_interval_sec, orbit_rk_step_sec, thermal_update_interval_sec, thermal_rk_step_sec, compo_propagate_step_sec, log_output_interval_sec, From a33076be9dab077139126bd2cc08e3402d993667 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 13:27:02 +0100 Subject: [PATCH 0016/1086] Modify Monte-carlo execution --- data/SampleSat/ini/SampleSimBase.ini | 8 ++++---- src/Simulation/MCSim/InitMcSim.cpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index 8dd49911a..faa5eb0d9 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -44,15 +44,15 @@ log_output_period_s = 0.1 // should be larger than 'simulation_step_s' simulation_speed_setting = 0 -[MC_EXECUTION] +[MonteCarloExecution] // Whether Monte-Carlo Simulation is executed or not -MCSimEnabled = DISABLE +monte_carlo_enable = DISABLE // Whether you want output the log file for each step -LogHistory = ENABLE +log_enable = ENABLE // Number of execution -NumOfExecutions = 100 +number_of_executions = 100 [MC_RANDOMIZATION] diff --git a/src/Simulation/MCSim/InitMcSim.cpp b/src/Simulation/MCSim/InitMcSim.cpp index e055f7e53..0acd2b57e 100644 --- a/src/Simulation/MCSim/InitMcSim.cpp +++ b/src/Simulation/MCSim/InitMcSim.cpp @@ -13,18 +13,18 @@ MCSimExecutor* InitMCSim(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "MC_EXECUTION"; + const char* section = "MonteCarloExecution"; - unsigned long long total_num_of_executions = ini_file.ReadInt(section, "NumOfExecutions"); + unsigned long long total_num_of_executions = ini_file.ReadInt(section, "number_of_executions"); MCSimExecutor* mc_sim = new MCSimExecutor(total_num_of_executions); char endis_str[MAX_CHAR_NUM]; - ini_file.ReadChar(section, "MCSimEnabled", MAX_CHAR_NUM, endis_str); + ini_file.ReadChar(section, "monte_carlo_enable", MAX_CHAR_NUM, endis_str); bool enable = (strcmp(endis_str, "ENABLED") == 0); mc_sim->Enable(enable); - ini_file.ReadChar(section, "LogHistory", MAX_CHAR_NUM, endis_str); + ini_file.ReadChar(section, "log_enable", MAX_CHAR_NUM, endis_str); bool log_history = (strcmp(endis_str, "ENABLED") == 0); mc_sim->LogHistory(log_history); From b51bf9e5d1d27399145e7dee654b0b056a7e1826 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 13:34:23 +0100 Subject: [PATCH 0017/1086] Modify Monte-carlo randomization --- data/SampleSat/ini/SampleSimBase.ini | 36 ++++++++++++++-------------- src/Simulation/MCSim/InitMcSim.cpp | 4 ++-- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index faa5eb0d9..f33f116a8 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -55,24 +55,24 @@ log_enable = ENABLE number_of_executions = 100 -[MC_RANDOMIZATION] -Param(0) = ATTITUDE0.Debug -ATTITUDE0.Debug.randomization_type = CartesianUniform -ATTITUDE0.Debug.mean_or_min(0) = 0.0 -ATTITUDE0.Debug.mean_or_min(1) = 0.0 -ATTITUDE0.Debug.mean_or_min(2) = 0.0 -ATTITUDE0.Debug.sigma_or_max(0) = 10.0 -ATTITUDE0.Debug.sigma_or_max(1) = 10.0 -ATTITUDE0.Debug.sigma_or_max(2) = 10.0 - -Param(1) = ATTITUDE0.Omega_b -ATTITUDE0.Omega_b.randomization_type = NoRandomization -ATTITUDE0.Omega_b.mean_or_min(0) = 0.0 -ATTITUDE0.Omega_b.mean_or_min(1) = 0.0 -ATTITUDE0.Omega_b.mean_or_min(2) = 0.0 -ATTITUDE0.Omega_b.sigma_or_max(0) = 0.05817764 // 3-sigma = 10 [deg/s] -ATTITUDE0.Omega_b.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] -ATTITUDE0.Omega_b.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] +[MonteCarloRandomization] +parameter(0) = attitude0.debug +attitude0.debug.randomization_type = CartesianUniform +attitude0.debug.mean_or_min(0) = 0.0 +attitude0.debug.mean_or_min(1) = 0.0 +attitude0.debug.mean_or_min(2) = 0.0 +attitude0.debug.sigma_or_max(0) = 10.0 +attitude0.debug.sigma_or_max(1) = 10.0 +attitude0.debug.sigma_or_max(2) = 10.0 + +parameter(1) = attitude0.omega_b +attitude0.omega_b.randomization_type = NoRandomization +attitude0.omega_b.mean_or_min(0) = 0.0 +attitude0.omega_b.mean_or_min(1) = 0.0 +attitude0.omega_b.mean_or_min(2) = 0.0 +attitude0.omega_b.sigma_or_max(0) = 0.05817764 // 3-sigma = 10 [deg/s] +attitude0.omega_b.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] +attitude0.omega_b.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] [PLANET_SELECTION] diff --git a/src/Simulation/MCSim/InitMcSim.cpp b/src/Simulation/MCSim/InitMcSim.cpp index 0acd2b57e..ca1efdb6e 100644 --- a/src/Simulation/MCSim/InitMcSim.cpp +++ b/src/Simulation/MCSim/InitMcSim.cpp @@ -28,8 +28,8 @@ MCSimExecutor* InitMCSim(std::string file_name) { bool log_history = (strcmp(endis_str, "ENABLED") == 0); mc_sim->LogHistory(log_history); - section = "MC_RANDOMIZATION"; - std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "Param"); + section = "MonteCarloRandomization"; + std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "parameter"); std::vector so_str_vec, ip_str_vec; enum Phase { FoundNothingYet, FoundSimulationObjectStr, FoundInitParameterStr }; From 75579a9b6b1e94f356a6088464688b2c145d6766 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 13:42:46 +0100 Subject: [PATCH 0018/1086] Modify CelestialInformation initialize --- data/SampleSat/ini/SampleSimBase.ini | 34 +++++++++---------- .../Global/InitGlobalEnvironment.cpp | 10 +++--- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index f33f116a8..a80cad19a 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -75,35 +75,35 @@ attitude0.omega_b.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] attitude0.omega_b.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] -[PLANET_SELECTION] +[CelestialInformation] // Whether global celestial information is logged or not logging = ENABLE // Definition of Inertial frame inertial_frame = J2000 -aberration_correction = NONE // The center object is also used to define the gravity constant of the center body center_object = EARTH +aberration_correction = NONE // Earth Rotation model -// Idle:no motion,Simple:rotation only,Full:full-dynamics +// Idle:no motion, Simple:rotation only, Full:full-dynamics rotation_mode = Simple // Definition of calculation celestial bodies -num_of_selected_body = 3 -selected_body(0) = EARTH -selected_body(1) = SUN -selected_body(2) = MOON -selected_body(3) = MERCURY -selected_body(4) = VENUS -selected_body(5) = MARS -selected_body(6) = JUPITER -selected_body(7) = SATURN -selected_body(8) = URANUS -selected_body(9) = NEPTUNE -selected_body(10) = PLUTO - -[FURNSH_PATH] +number_of_selected_body = 3 +selected_body_name(0) = EARTH +selected_body_name(1) = SUN +selected_body_name(2) = MOON +selected_body_name(3) = MERCURY +selected_body_name(4) = VENUS +selected_body_name(5) = MARS +selected_body_name(6) = JUPITER +selected_body_name(7) = SATURN +selected_body_name(8) = URANUS +selected_body_name(9) = NEPTUNE +selected_body_name(10) = PLUTO + +[CSPICE_KERNELS] // CSPICE Kernel files definition TLS = ../../../ExtLibraries/cspice/generic_kernels/lsk/naif0010.tls TPC1 = ../../../ExtLibraries/cspice/generic_kernels/pck/de-403-masses.tpc diff --git a/src/Environment/Global/InitGlobalEnvironment.cpp b/src/Environment/Global/InitGlobalEnvironment.cpp index 54337c23e..cb66fe957 100644 --- a/src/Environment/Global/InitGlobalEnvironment.cpp +++ b/src/Environment/Global/InitGlobalEnvironment.cpp @@ -63,8 +63,8 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name) { CelestialInformation* InitCelesInfo(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "PLANET_SELECTION"; - const char* furnsh_section = "FURNSH_PATH"; + const char* section = "CelestialInformation"; + const char* furnsh_section = "CspiceKernels"; // Read SPICE setting std::string inertial_frame = ini_file.ReadString(section, "inertial_frame"); @@ -72,18 +72,18 @@ CelestialInformation* InitCelesInfo(std::string file_name) { std::string center_obj = ini_file.ReadString(section, "center_object"); // SPICE Furnsh - std::vector keywords = {"TLS", "TPC1", "TPC2", "TPC3", "BSP"}; + std::vector keywords = {"tls", "tpc1", "tpc2", "tpc3", "bsp"}; for (size_t i = 0; i < keywords.size(); i++) { std::string fname = ini_file.ReadString(furnsh_section, keywords[i].c_str()); furnsh_c(fname.c_str()); } // Initialize celestial body list - const int num_of_selected_body = ini_file.ReadInt(section, "num_of_selected_body"); + const int num_of_selected_body = ini_file.ReadInt(section, "number_of_selected_body"); int* selected_body = new int[num_of_selected_body]; for (int i = 0; i < num_of_selected_body; i++) { // Convert body name to SPICE ID - std::string selected_body_i = "selected_body(" + std::to_string(i) + ")"; + std::string selected_body_i = "selected_body_name(" + std::to_string(i) + ")"; char selected_body_temp[30]; ini_file.ReadChar(section, selected_body_i.c_str(), 30, selected_body_temp); SpiceInt planet_id; From 106544054404a094eec349bdc02014d5c4931f28 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 13:46:28 +0100 Subject: [PATCH 0019/1086] Modify HipparcosCatalogue initialize --- data/SampleSat/ini/SampleSimBase.ini | 24 +++++++++---------- .../Global/InitGlobalEnvironment.cpp | 4 ++-- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index a80cad19a..f0bf0926d 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -103,30 +103,30 @@ selected_body_name(8) = URANUS selected_body_name(9) = NEPTUNE selected_body_name(10) = PLUTO -[CSPICE_KERNELS] +[CspiceKernels] // CSPICE Kernel files definition -TLS = ../../../ExtLibraries/cspice/generic_kernels/lsk/naif0010.tls -TPC1 = ../../../ExtLibraries/cspice/generic_kernels/pck/de-403-masses.tpc -TPC2 = ../../../ExtLibraries/cspice/generic_kernels/pck/gm_de431.tpc -TPC3 = ../../../ExtLibraries/cspice/generic_kernels/pck/pck00010.tpc -BSP = ../../../ExtLibraries/cspice/generic_kernels/spk/planets/de430.bsp +tls = ../../../ExtLibraries/cspice/generic_kernels/lsk/naif0010.tls +tpc1 = ../../../ExtLibraries/cspice/generic_kernels/pck/de-403-masses.tpc +tpc2 = ../../../ExtLibraries/cspice/generic_kernels/pck/gm_de431.tpc +tpc3 = ../../../ExtLibraries/cspice/generic_kernels/pck/pck00010.tpc +bsp = ../../../ExtLibraries/cspice/generic_kernels/spk/planets/de430.bsp -[HIPPARCOS_CATALOGUE] -catalogue_path = ../../../ExtLibraries/HipparcosCatalogue/hip_main.csv +[HipparcosCatalogue] +catalogue_file_path = ../../../ExtLibraries/HipparcosCatalogue/hip_main.csv max_magnitude = 3.0 // Max magnitude to read from Hip catalog calculation = DISABLE logging = DISABLE -[RAND] +[Randomize] // Seed of randam. When this value is 0, the seed will be varied by time. -Rand_Seed = 0x11223344 +rand_seed = 0x11223344 -[SIM_SETTING] +[SimulationSetting] // Whether the ini files are saved or not -log_inifile = 1 +save_initialize_files = 1 // Initialize files // File name must not over 256 characters (defined in initialize.h as MAX_CHAR_NUM) diff --git a/src/Environment/Global/InitGlobalEnvironment.cpp b/src/Environment/Global/InitGlobalEnvironment.cpp index cb66fe957..2f7a7d8b1 100644 --- a/src/Environment/Global/InitGlobalEnvironment.cpp +++ b/src/Environment/Global/InitGlobalEnvironment.cpp @@ -47,10 +47,10 @@ SimTime* InitSimTime(std::string file_name) { HipparcosCatalogue* InitHipCatalogue(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "HIPPARCOS_CATALOGUE"; + const char* section = "HipparcosCatalogue"; + std::string catalogue_path = ini_file.ReadString(section, "catalogue_file_path"); double max_magnitude = ini_file.ReadDouble(section, "max_magnitude"); - std::string catalogue_path = ini_file.ReadString(section, "catalogue_path"); HipparcosCatalogue* hip_catalogue; hip_catalogue = new HipparcosCatalogue(max_magnitude, catalogue_path); From 0df521f4c6701f35880d598ad4394fc2d9ef2a94 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 14:09:07 +0100 Subject: [PATCH 0020/1086] Modify SimulationSetting --- data/SampleSat/ini/SampleSimBase.ini | 13 ++++++------- src/Interface/LogOutput/InitLog.cpp | 8 ++++---- src/Simulation/Case/SimulationCase.cpp | 12 ++++++------ 3 files changed, 16 insertions(+), 17 deletions(-) diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/SampleSat/ini/SampleSimBase.ini index f0bf0926d..6659c89f0 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/SampleSat/ini/SampleSimBase.ini @@ -126,14 +126,13 @@ rand_seed = 0x11223344 [SimulationSetting] // Whether the ini files are saved or not -save_initialize_files = 1 +save_initialize_files = ENABLE // Initialize files // File name must not over 256 characters (defined in initialize.h as MAX_CHAR_NUM) // If you want to add a spacecraft, create the corresponding Sat.ini, and specify it as sat_file(1), sat_file(2)... . -num_of_simulated_spacecraft = 1 -sat_file(0) = ../../data/SampleSat/ini/SampleSat.ini -gs_file = ../../data/SampleSat/ini/SampleGS.ini -inter_sat_comm_file = ../../data/SampleSat/ini/SampleInterSatComm.ini -gnss_file = ../../data/SampleSat/ini/SampleGNSS.ini -log_file_path = ../../data/SampleSat/logs/ +number_of_simulated_spacecraft = 1 +spacecraft_file(0) = ../../data/SampleSat/ini/SampleSat.ini +ground_station_file = ../../data/SampleSat/ini/SampleGS.ini +gnss_file = ../../data/SampleSat/ini/SampleGNSS.ini +log_file_save_directory = ../../data/SampleSat/logs/ diff --git a/src/Interface/LogOutput/InitLog.cpp b/src/Interface/LogOutput/InitLog.cpp index cb715535d..2191a285a 100644 --- a/src/Interface/LogOutput/InitLog.cpp +++ b/src/Interface/LogOutput/InitLog.cpp @@ -10,8 +10,8 @@ Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); - std::string log_file_path = ini_file.ReadString("SIM_SETTING", "log_file_path"); - bool log_ini = ini_file.ReadBoolean("SIM_SETTING", "log_inifile"); + std::string log_file_path = ini_file.ReadString("SimulationSetting", "log_file_save_directory"); + bool log_ini = ini_file.ReadEnable("SimulationSetting", "save_initialize_files"); Logger* log = new Logger("default.csv", log_file_path, file_name, log_ini, true); @@ -21,8 +21,8 @@ Logger* InitLog(std::string file_name) { Logger* InitLogMC(std::string file_name, bool enable) { IniAccess ini_file(file_name); - std::string log_file_path = ini_file.ReadString("SIM_SETTING", "log_file_path"); - bool log_ini = ini_file.ReadBoolean("SIM_SETTING", "log_inifile"); + std::string log_file_path = ini_file.ReadString("SimulationSetting", "log_file_save_directory"); + bool log_ini = ini_file.ReadEnable("SimulationSetting", "save_initialize_files"); Logger* log = new Logger("mont.csv", log_file_path, file_name, log_ini, enable); diff --git a/src/Simulation/Case/SimulationCase.cpp b/src/Simulation/Case/SimulationCase.cpp index 2fed82acd..3af411daa 100644 --- a/src/Simulation/Case/SimulationCase.cpp +++ b/src/Simulation/Case/SimulationCase.cpp @@ -12,25 +12,25 @@ SimulationCase::SimulationCase(std::string ini_base) { IniAccess simbase_ini = IniAccess(ini_base); - const char* section = "SIM_SETTING"; + const char* section = "SimulationSetting"; sim_config_.ini_base_fname_ = ini_base; sim_config_.main_logger_ = InitLog(sim_config_.ini_base_fname_); - sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "num_of_simulated_spacecraft"); - sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "sat_file"); - sim_config_.gs_file_ = simbase_ini.ReadString(section, "gs_file"); + sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); + sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + sim_config_.gs_file_ = simbase_ini.ReadString(section, "ground_station_file"); sim_config_.inter_sat_comm_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); glo_env_ = new GlobalEnvironment(&sim_config_); } SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); - const char* section = "SIM_SETTING"; + const char* section = "SimulationSetting"; sim_config_.ini_base_fname_ = ini_base; // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(mc_sim.GetNumOfExecutionsDone()) + ".csv"; // ToDo: Consider that `enable_inilog = false` is fine or not? sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, mc_sim.LogHistory()); - sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "num_of_simulated_spacecraft"); + sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "sat_file"); sim_config_.gs_file_ = simbase_ini.ReadString(section, "gs_file"); sim_config_.inter_sat_comm_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); From 4767f87265c5c0e0b3d9ac8609627f8bbafd08e2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 14:15:35 +0100 Subject: [PATCH 0021/1086] Fix MonteCarlo enable flag reading --- src/Simulation/MCSim/InitMcSim.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/Simulation/MCSim/InitMcSim.cpp b/src/Simulation/MCSim/InitMcSim.cpp index ca1efdb6e..debb4b653 100644 --- a/src/Simulation/MCSim/InitMcSim.cpp +++ b/src/Simulation/MCSim/InitMcSim.cpp @@ -19,13 +19,10 @@ MCSimExecutor* InitMCSim(std::string file_name) { MCSimExecutor* mc_sim = new MCSimExecutor(total_num_of_executions); - char endis_str[MAX_CHAR_NUM]; - ini_file.ReadChar(section, "monte_carlo_enable", MAX_CHAR_NUM, endis_str); - bool enable = (strcmp(endis_str, "ENABLED") == 0); + bool enable = ini_file.ReadEnable(section, "monte_carlo_enable"); mc_sim->Enable(enable); - ini_file.ReadChar(section, "log_enable", MAX_CHAR_NUM, endis_str); - bool log_history = (strcmp(endis_str, "ENABLED") == 0); + bool log_history = ini_file.ReadEnable(section, "log_enable"); mc_sim->LogHistory(log_history); section = "MonteCarloRandomization"; From d18cbb966bc9beab82377f34777c64618c80ad46 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 14:36:36 +0100 Subject: [PATCH 0022/1086] Modify axis description --- src/Interface/LogOutput/LogUtility.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Interface/LogOutput/LogUtility.h b/src/Interface/LogOutput/LogUtility.h index 975375b07..1e8f8d45b 100644 --- a/src/Interface/LogOutput/LogUtility.h +++ b/src/Interface/LogOutput/LogUtility.h @@ -97,7 +97,7 @@ std::string WriteVector(Vector vec, int precision) { } std::string WriteVector(std::string name, std::string frame, std::string unit, size_t n) { std::stringstream str_tmp; - std::string axis[3] = {"(X)", "(Y)", "(Z)"}; + std::string axis[3] = {"_x", "_y", "_z"}; for (size_t i = 0; i < n; i++) { if (n == 3) { From 75263227cbf9109658a6b7879d539f3a6e032217 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 14:36:48 +0100 Subject: [PATCH 0023/1086] Modify time log --- src/Environment/Global/SimTime.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Environment/Global/SimTime.cpp b/src/Environment/Global/SimTime.cpp index f1be4bd75..4dccca830 100644 --- a/src/Environment/Global/SimTime.cpp +++ b/src/Environment/Global/SimTime.cpp @@ -193,7 +193,7 @@ void SimTime::PrintStartDateTime(void) const { string SimTime::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteScalar("time", "sec"); + str_tmp += WriteScalar("time", "s"); return str_tmp; } From 0b82bed46698b93f0b1070462d9bfb61a64c84e1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 14:48:09 +0100 Subject: [PATCH 0024/1086] Modify CelestialInformation log output --- src/Environment/Global/CelestialInformation.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/Environment/Global/CelestialInformation.cpp b/src/Environment/Global/CelestialInformation.cpp index 194bee7cb..c164b06ae 100644 --- a/src/Environment/Global/CelestialInformation.cpp +++ b/src/Environment/Global/CelestialInformation.cpp @@ -10,6 +10,7 @@ #include #include +#include #include #include @@ -202,9 +203,10 @@ string CelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); string name = namebuf; - string body_pos = name + "_pos"; - string body_vel = name + "_vel"; - // OUTPUT ONLY POS/VEL LOOKED FROM S/C AT THIS MOMENT + std::transform(name.begin(), name.end(), name.begin(), ::tolower); + string body_pos = name + "_position"; + string body_vel = name + "_velocity"; + str_tmp += WriteVector(body_pos, "i", "m", 3); str_tmp += WriteVector(body_vel, "i", "m/s", 3); } @@ -214,7 +216,6 @@ string CelestialInformation::GetLogHeader() const { string CelestialInformation::GetLogValue() const { string str_tmp = ""; for (int i = 0; i < num_of_selected_body_; i++) { - // OUTPUT ONLY POS/VEL LOOKED FROM S/C AT THIS MOMENT for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celes_objects_pos_from_center_i_[i * 3 + j]); } From 4bf96b18aa4d3ebebb539e88a8e971bcd2c8470d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:04:56 +0100 Subject: [PATCH 0025/1086] Fix ground station ini file access --- src/Simulation/Case/SimulationCase.cpp | 4 ++-- src/Simulation/GroundStation/GroundStation.cpp | 3 +-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/Simulation/Case/SimulationCase.cpp b/src/Simulation/Case/SimulationCase.cpp index 3af411daa..402df2ed2 100644 --- a/src/Simulation/Case/SimulationCase.cpp +++ b/src/Simulation/Case/SimulationCase.cpp @@ -31,8 +31,8 @@ SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim // ToDo: Consider that `enable_inilog = false` is fine or not? sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, mc_sim.LogHistory()); sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "sat_file"); - sim_config_.gs_file_ = simbase_ini.ReadString(section, "gs_file"); + sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + sim_config_.gs_file_ = simbase_ini.ReadString(section, "ground_station_file"); sim_config_.inter_sat_comm_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); // Global Environment diff --git a/src/Simulation/GroundStation/GroundStation.cpp b/src/Simulation/GroundStation/GroundStation.cpp index 12cde16b6..d51a9f188 100644 --- a/src/Simulation/GroundStation/GroundStation.cpp +++ b/src/Simulation/GroundStation/GroundStation.cpp @@ -25,8 +25,7 @@ GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id GroundStation::~GroundStation() {} void GroundStation::Initialize(int gs_id, SimulationConfig* config) { - IniAccess iniAccess = IniAccess(config->ini_base_fname_); - std::string gs_ini_path = iniAccess.ReadString("SIM_SETTING", "gs_file"); + std::string gs_ini_path = config->gs_file_; auto conf = IniAccess(gs_ini_path); const char* section_base = "GS"; From 1a4257c00534cffb28634e3f68bd1672956de220 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:15:28 +0100 Subject: [PATCH 0026/1086] Add WriteQuaternion function for CSV header --- src/Interface/LogOutput/LogUtility.h | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/Interface/LogOutput/LogUtility.h b/src/Interface/LogOutput/LogUtility.h index 1e8f8d45b..904437bd2 100644 --- a/src/Interface/LogOutput/LogUtility.h +++ b/src/Interface/LogOutput/LogUtility.h @@ -74,6 +74,13 @@ inline std::string WriteMatrix(std::string name, std::string frame, std::string * @note TODO: add function for headers? */ inline std::string WriteQuaternion(Quaternion quat); +/** + * @fn WriteQuaternion + * @brief Write header for quaternion + * @param [in] name: Name of the value + * @param [in] frame: Frame of the quaternion + */ +inline std::string WriteQuaternion(std::string name, std::string frame); // // Libraries for log writing @@ -141,3 +148,12 @@ std::string WriteQuaternion(Quaternion quat) { } return str_tmp.str(); } +std::string WriteQuaternion(std::string name, std::string frame) { + std::stringstream str_tmp; + std::string axis[4] = {"_x", "_y", "_z", "_w"}; + + for (size_t i = 0; i < 4; i++) { + str_tmp << name << "_" << frame << axis[i] << ","; + } + return str_tmp.str(); +} From e0af253e40abca2b035a23076d8ebfa8e67f6a76 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:15:44 +0100 Subject: [PATCH 0027/1086] Fix logoutput for attitude --- src/Dynamics/Attitude/Attitude.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/Dynamics/Attitude/Attitude.cpp b/src/Dynamics/Attitude/Attitude.cpp index 88524013e..a6882f8ad 100644 --- a/src/Dynamics/Attitude/Attitude.cpp +++ b/src/Dynamics/Attitude/Attitude.cpp @@ -21,11 +21,11 @@ Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_ob std::string Attitude::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteVector("omega_true", "b", "rad/s", 3); - str_tmp += WriteVector("quaternion_true", "i2b", "-", 4); - str_tmp += WriteVector("torque_true", "b", "Nm", 3); - str_tmp += WriteScalar("h_total", "Nms"); - str_tmp += WriteScalar("k_sc", "J"); + str_tmp += WriteVector("angular_velocity", "b", "rad/s", 3); + str_tmp += WriteQuaternion("quaternion", "i2b"); + str_tmp += WriteVector("torque", "b", "Nm", 3); + str_tmp += WriteScalar("total_angular_momentum", "Nms"); + str_tmp += WriteScalar("kinematic_energy", "J"); return str_tmp; } From 0c19c25ee08f1f7712118195c4d1e9d7eba14ec7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:18:17 +0100 Subject: [PATCH 0028/1086] Add spacecraft --- src/Dynamics/Attitude/Attitude.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/Dynamics/Attitude/Attitude.cpp b/src/Dynamics/Attitude/Attitude.cpp index a6882f8ad..91979cac2 100644 --- a/src/Dynamics/Attitude/Attitude.cpp +++ b/src/Dynamics/Attitude/Attitude.cpp @@ -21,11 +21,11 @@ Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_ob std::string Attitude::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteVector("angular_velocity", "b", "rad/s", 3); - str_tmp += WriteQuaternion("quaternion", "i2b"); - str_tmp += WriteVector("torque", "b", "Nm", 3); - str_tmp += WriteScalar("total_angular_momentum", "Nms"); - str_tmp += WriteScalar("kinematic_energy", "J"); + str_tmp += WriteVector("spacecraft_angular_velocity", "b", "rad/s", 3); + str_tmp += WriteQuaternion("spacecraft_quaternion", "i2b"); + str_tmp += WriteVector("spacecraft_torque", "b", "Nm", 3); + str_tmp += WriteScalar("spacecraft_total_angular_momentum", "Nms"); + str_tmp += WriteScalar("spacecraft_kinematic_energy", "J"); return str_tmp; } From 49c141bd3fda4f2ae96caee288da57f9e7887f5a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:26:19 +0100 Subject: [PATCH 0029/1086] Fix Orbit log output --- src/Dynamics/Orbit/EnckeOrbitPropagation.cpp | 26 --------------- src/Dynamics/Orbit/EnckeOrbitPropagation.h | 12 ------- src/Dynamics/Orbit/KeplerOrbitPropagation.cpp | 28 ---------------- src/Dynamics/Orbit/KeplerOrbitPropagation.h | 12 ------- src/Dynamics/Orbit/Orbit.cpp | 30 ++++++++++++++++- src/Dynamics/Orbit/Orbit.h | 4 +-- src/Dynamics/Orbit/RelativeOrbit.cpp | 32 ------------------- src/Dynamics/Orbit/RelativeOrbit.h | 12 ------- src/Dynamics/Orbit/Rk4OrbitPropagation.cpp | 28 ---------------- src/Dynamics/Orbit/Rk4OrbitPropagation.h | 12 ------- src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp | 28 ---------------- src/Dynamics/Orbit/Sgp4OrbitPropagation.h | 12 ------- 12 files changed, 31 insertions(+), 205 deletions(-) diff --git a/src/Dynamics/Orbit/EnckeOrbitPropagation.cpp b/src/Dynamics/Orbit/EnckeOrbitPropagation.cpp index 513d09331..954f6b81c 100644 --- a/src/Dynamics/Orbit/EnckeOrbitPropagation.cpp +++ b/src/Dynamics/Orbit/EnckeOrbitPropagation.cpp @@ -55,32 +55,6 @@ void EnckeOrbitPropagation::Propagate(double endtime, double current_jd) { UpdateSatOrbit(); } -std::string EnckeOrbitPropagation::GetLogHeader() const { - std::string str_tmp = ""; - - str_tmp += WriteVector("sat_position", "i", "m", 3); - str_tmp += WriteVector("sat_velocity", "i", "m/s", 3); - str_tmp += WriteVector("sat_velocity", "b", "m/s", 3); - str_tmp += WriteVector("sat_acc", "i", "m/s^2", 3); - str_tmp += WriteScalar("lat", "rad"); - str_tmp += WriteScalar("lon", "rad"); - str_tmp += WriteScalar("alt", "m"); - return str_tmp; -} - -std::string EnckeOrbitPropagation::GetLogValue() const { - std::string str_tmp = ""; - - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); - return str_tmp; -} - // Functions for ODE void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) { UNUSED(t); diff --git a/src/Dynamics/Orbit/EnckeOrbitPropagation.h b/src/Dynamics/Orbit/EnckeOrbitPropagation.h index 40cc7f03c..a72354242 100644 --- a/src/Dynamics/Orbit/EnckeOrbitPropagation.h +++ b/src/Dynamics/Orbit/EnckeOrbitPropagation.h @@ -41,18 +41,6 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { */ virtual void Propagate(double endtime, double current_jd); - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - // Override ODE /** * @fn RHS diff --git a/src/Dynamics/Orbit/KeplerOrbitPropagation.cpp b/src/Dynamics/Orbit/KeplerOrbitPropagation.cpp index 775c2d234..956765e94 100644 --- a/src/Dynamics/Orbit/KeplerOrbitPropagation.cpp +++ b/src/Dynamics/Orbit/KeplerOrbitPropagation.cpp @@ -23,34 +23,6 @@ void KeplerOrbitPropagation::Propagate(double endtime, double current_jd) { UpdateState(current_jd); } -std::string KeplerOrbitPropagation::GetLogHeader() const { - std::string str_tmp = ""; - - str_tmp += WriteVector("sat_position", "i", "m", 3); - str_tmp += WriteVector("sat_velocity", "i", "m/s", 3); - str_tmp += WriteVector("sat_velocity", "b", "m/s", 3); - str_tmp += WriteVector("sat_acc_i", "i", "m/s^2", 3); - str_tmp += WriteScalar("lat", "rad"); - str_tmp += WriteScalar("lon", "rad"); - str_tmp += WriteScalar("alt", "m"); - - return str_tmp; -} - -std::string KeplerOrbitPropagation::GetLogValue() const { - std::string str_tmp = ""; - - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); - - return str_tmp; -} - // Private Function void KeplerOrbitPropagation::UpdateState(const double current_jd) { CalcPosVel(current_jd); diff --git a/src/Dynamics/Orbit/KeplerOrbitPropagation.h b/src/Dynamics/Orbit/KeplerOrbitPropagation.h index 5ae4fba68..22b64c36a 100644 --- a/src/Dynamics/Orbit/KeplerOrbitPropagation.h +++ b/src/Dynamics/Orbit/KeplerOrbitPropagation.h @@ -36,18 +36,6 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { */ virtual void Propagate(double endtime, double current_jd); - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - private: /** * @fn UpdateState diff --git a/src/Dynamics/Orbit/Orbit.cpp b/src/Dynamics/Orbit/Orbit.cpp index b3bac865b..974a55d0d 100644 --- a/src/Dynamics/Orbit/Orbit.cpp +++ b/src/Dynamics/Orbit/Orbit.cpp @@ -51,4 +51,32 @@ OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode) { } else { return OrbitInitializeMode::kDefault; } -} \ No newline at end of file +} + +std::string Orbit::GetLogHeader() const { + std::string str_tmp = ""; + + str_tmp += WriteVector("spacecraft_position", "i", "m", 3); + str_tmp += WriteVector("spacecraft_velocity", "i", "m/s", 3); + str_tmp += WriteVector("spacecraft_velocity", "b", "m/s", 3); + str_tmp += WriteVector("spacecraft_acceleration_i", "i", "m/s2", 3); + str_tmp += WriteScalar("spacecraft_latitude", "rad"); + str_tmp += WriteScalar("spacecraft_longitude", "rad"); + str_tmp += WriteScalar("spacecraft_altitude", "m"); + + return str_tmp; +} + +std::string Orbit::GetLogValue() const { + std::string str_tmp = ""; + + str_tmp += WriteVector(sat_position_i_, 16); + str_tmp += WriteVector(sat_velocity_i_, 10); + str_tmp += WriteVector(sat_velocity_b_, 10); + str_tmp += WriteVector(acc_i_, 10); + str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); + str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); + str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); + + return str_tmp; +} diff --git a/src/Dynamics/Orbit/Orbit.h b/src/Dynamics/Orbit/Orbit.h index c41df166a..fbdd876db 100644 --- a/src/Dynamics/Orbit/Orbit.h +++ b/src/Dynamics/Orbit/Orbit.h @@ -187,12 +187,12 @@ class Orbit : public ILoggable { * @fn GetLogHeader * @brief Override GetLogHeader function of ILoggable */ - virtual std::string GetLogHeader() const = 0; + virtual std::string GetLogHeader() const; /** * @fn GetLogValue * @brief Override GetLogValue function of ILoggable */ - virtual std::string GetLogValue() const = 0; + virtual std::string GetLogValue() const; protected: const CelestialInformation* celes_info_; //!< Celestial information diff --git a/src/Dynamics/Orbit/RelativeOrbit.cpp b/src/Dynamics/Orbit/RelativeOrbit.cpp index 4c59eec1b..24bd8ab7b 100644 --- a/src/Dynamics/Orbit/RelativeOrbit.cpp +++ b/src/Dynamics/Orbit/RelativeOrbit.cpp @@ -150,35 +150,3 @@ void RelativeOrbit::RHS(double t, const Vector<6>& state, Vector<6>& rhs) // on rhs = system_matrix_ * state; (void)t; } - -std::string RelativeOrbit::GetLogHeader() const { - std::string str_tmp = ""; - - str_tmp += WriteVector("sat_position", "i", "m", 3); - str_tmp += WriteVector("sat_velocity", "i", "m/s", 3); - str_tmp += WriteVector("sat_velocity", "b", "m/s", 3); - str_tmp += WriteVector("sat_position_relative_to_sat" + std::to_string(reference_sat_id_), "LVLH", "m", 3); - str_tmp += WriteVector("sat_velocity_relative_to_sat" + std::to_string(reference_sat_id_), "LVLH", "m", 3); - str_tmp += WriteVector("sat_acc_i", "i", "m/s^2", 3); - str_tmp += WriteScalar("lat", "rad"); - str_tmp += WriteScalar("lon", "rad"); - str_tmp += WriteScalar("alt", "m"); - - return str_tmp; -} - -std::string RelativeOrbit::GetLogValue() const { - std::string str_tmp = ""; - - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(relative_position_lvlh_, 10); - str_tmp += WriteVector(relative_velocity_lvlh_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); - - return str_tmp; -} diff --git a/src/Dynamics/Orbit/RelativeOrbit.h b/src/Dynamics/Orbit/RelativeOrbit.h index 6f3e4972a..0f1203fcf 100644 --- a/src/Dynamics/Orbit/RelativeOrbit.h +++ b/src/Dynamics/Orbit/RelativeOrbit.h @@ -64,18 +64,6 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { */ virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - private: double mu_; //!< Gravity constant of the center body [m3/s2] int reference_sat_id_; //!< Reference satellite ID diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.cpp b/src/Dynamics/Orbit/Rk4OrbitPropagation.cpp index d3d8e3d77..9f02a1ac0 100644 --- a/src/Dynamics/Orbit/Rk4OrbitPropagation.cpp +++ b/src/Dynamics/Orbit/Rk4OrbitPropagation.cpp @@ -99,31 +99,3 @@ void Rk4OrbitPropagation::AddPositionOffset(Vector<3> offset_i) { sat_position_i_[1] = state()[1]; sat_position_i_[2] = state()[2]; } - -string Rk4OrbitPropagation::GetLogHeader() const { - string str_tmp = ""; - - str_tmp += WriteVector("sat_position", "i", "m", 3); - str_tmp += WriteVector("sat_velocity", "i", "m/s", 3); - str_tmp += WriteVector("sat_velocity", "b", "m/s", 3); - str_tmp += WriteVector("sat_acc_i", "i", "m/s^2", 3); - str_tmp += WriteScalar("lat", "rad"); - str_tmp += WriteScalar("lon", "rad"); - str_tmp += WriteScalar("alt", "m"); - - return str_tmp; -} - -string Rk4OrbitPropagation::GetLogValue() const { - string str_tmp = ""; - - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); - - return str_tmp; -} diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.h b/src/Dynamics/Orbit/Rk4OrbitPropagation.h index d5b2cf90f..0f43db05d 100644 --- a/src/Dynamics/Orbit/Rk4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Rk4OrbitPropagation.h @@ -63,18 +63,6 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { */ virtual void AddPositionOffset(Vector<3> offset_i); - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - private: double prop_time_; //!< Simulation current time for numerical integration by RK4 [sec] double prop_step_; //!< Step width for RK4 [sec] diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp b/src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp index 614142d0d..9ca035e8b 100644 --- a/src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp +++ b/src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp @@ -58,34 +58,6 @@ void Sgp4OrbitPropagation::Propagate(double endtime, double current_jd) { TransEcefToGeo(); } -string Sgp4OrbitPropagation::GetLogHeader() const { - string str_tmp = ""; - - str_tmp += WriteVector("sat_position", "i", "m", 3); - str_tmp += WriteVector("sat_velocity", "i", "m/s", 3); - str_tmp += WriteVector("sat_velocity", "b", "m/s", 3); - str_tmp += WriteVector("sat_acc_i", "i", "m/s^2", 3); - str_tmp += WriteScalar("lat", "rad"); - str_tmp += WriteScalar("lon", "rad"); - str_tmp += WriteScalar("alt", "m"); - - return str_tmp; -} - -string Sgp4OrbitPropagation::GetLogValue() const { - string str_tmp = ""; - - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); - - return str_tmp; -} - Vector<3> Sgp4OrbitPropagation::GetESIOmega() { Vector<3> omega_peri = Vector<3>(); omega_peri[0] = 0.0; diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h index 383926557..a3e5f0914 100644 --- a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h @@ -42,18 +42,6 @@ class Sgp4OrbitPropagation : public Orbit { */ Vector<3> GetESIOmega(); - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - private: gravconsttype whichconst_; //!< Gravity constant value type elsetrec satrec_; //!< Structure data for SGP4 library From cff531ec8daa5d5751b43505883b20f6d2c73565 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:28:18 +0100 Subject: [PATCH 0030/1086] Fix small --- src/Dynamics/Orbit/Orbit.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Dynamics/Orbit/Orbit.cpp b/src/Dynamics/Orbit/Orbit.cpp index 974a55d0d..675a6c628 100644 --- a/src/Dynamics/Orbit/Orbit.cpp +++ b/src/Dynamics/Orbit/Orbit.cpp @@ -59,7 +59,7 @@ std::string Orbit::GetLogHeader() const { str_tmp += WriteVector("spacecraft_position", "i", "m", 3); str_tmp += WriteVector("spacecraft_velocity", "i", "m/s", 3); str_tmp += WriteVector("spacecraft_velocity", "b", "m/s", 3); - str_tmp += WriteVector("spacecraft_acceleration_i", "i", "m/s2", 3); + str_tmp += WriteVector("spacecraft_acceleration", "i", "m/s2", 3); str_tmp += WriteScalar("spacecraft_latitude", "rad"); str_tmp += WriteScalar("spacecraft_longitude", "rad"); str_tmp += WriteScalar("spacecraft_altitude", "m"); From 7f70746e96b4fb9e31ab7f72cd67aa81275e2ceb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:30:05 +0100 Subject: [PATCH 0031/1086] Fix Geomagnetic field log --- src/Environment/Local/MagEnvironment.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Environment/Local/MagEnvironment.cpp b/src/Environment/Local/MagEnvironment.cpp index cf5572788..c870dac6e 100644 --- a/src/Environment/Local/MagEnvironment.cpp +++ b/src/Environment/Local/MagEnvironment.cpp @@ -60,8 +60,8 @@ Vector<3> MagEnvironment::GetMag_b() const { return Mag_b_; } string MagEnvironment::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteVector("mag", "i", "nT", 3); - str_tmp += WriteVector("mag", "b", "nT", 3); + str_tmp += WriteVector("geomagnetic_field", "i", "nT", 3); + str_tmp += WriteVector("geomagnetic_field", "b", "nT", 3); return str_tmp; } From 48210f834822920399efabbe025054ee93c31139 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:31:18 +0100 Subject: [PATCH 0032/1086] Describe more detail --- src/Environment/Local/MagEnvironment.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Environment/Local/MagEnvironment.cpp b/src/Environment/Local/MagEnvironment.cpp index c870dac6e..30fa63d3c 100644 --- a/src/Environment/Local/MagEnvironment.cpp +++ b/src/Environment/Local/MagEnvironment.cpp @@ -60,8 +60,8 @@ Vector<3> MagEnvironment::GetMag_b() const { return Mag_b_; } string MagEnvironment::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteVector("geomagnetic_field", "i", "nT", 3); - str_tmp += WriteVector("geomagnetic_field", "b", "nT", 3); + str_tmp += WriteVector("geomagnetic_field_at_spacecraft_position", "i", "nT", 3); + str_tmp += WriteVector("geomagnetic_field_at_spacecraft_position", "b", "nT", 3); return str_tmp; } From cb425de7ce8cc9a6c53099603fe5b79294be471d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:36:00 +0100 Subject: [PATCH 0033/1086] Fix log output for local environment --- src/Environment/Local/Atmosphere.cpp | 2 +- src/Environment/Local/SRPEnvironment.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/Environment/Local/Atmosphere.cpp b/src/Environment/Local/Atmosphere.cpp index 25859617e..034ee21da 100644 --- a/src/Environment/Local/Atmosphere.cpp +++ b/src/Environment/Local/Atmosphere.cpp @@ -228,7 +228,7 @@ string Atmosphere::GetLogValue() const { string Atmosphere::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteScalar("airdensity", "kg/m^3"); + str_tmp += WriteScalar("air_density_at_spacecraft_position", "kg/m3"); return str_tmp; } diff --git a/src/Environment/Local/SRPEnvironment.cpp b/src/Environment/Local/SRPEnvironment.cpp index 5ac90f797..77fdc9a74 100644 --- a/src/Environment/Local/SRPEnvironment.cpp +++ b/src/Environment/Local/SRPEnvironment.cpp @@ -49,8 +49,8 @@ double SRPEnvironment::GetShadowCoefficient() const { return shadow_coefficient_ string SRPEnvironment::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteScalar("sr_pressure", "N/m^2"); - str_tmp += WriteScalar("shadow coefficient"); + str_tmp += WriteScalar("solar_radiation_pressure_at_spacecraft_position", "N/m2"); + str_tmp += WriteScalar("shadow_coefficient_at_spacecraft_position"); return str_tmp; } From 4766ad3ef7c8fc326d38b3cc164dc14a6514b2bd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:39:19 +0100 Subject: [PATCH 0034/1086] Fix local celestial information log --- src/Environment/Local/LocalCelestialInformation.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/Environment/Local/LocalCelestialInformation.cpp b/src/Environment/Local/LocalCelestialInformation.cpp index 083ad41b9..270f1b60a 100644 --- a/src/Environment/Local/LocalCelestialInformation.cpp +++ b/src/Environment/Local/LocalCelestialInformation.cpp @@ -8,6 +8,7 @@ #include #include +#include #include #include @@ -168,9 +169,9 @@ string LocalCelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); string name = namebuf; - string body_pos = name + "_pos"; - string body_vel = name + "_vel"; - //  OUTPUT ONLY POS/VEL LOOKED FROM S/C AT THIS MOMENT + std::transform(name.begin(), name.end(), name.begin(), ::tolower); + string body_pos = name + "_position_from_spacecraft"; + string body_vel = name + "_velocity_from_spacecraft"; str_tmp += WriteVector(body_pos, "b", "m", 3); str_tmp += WriteVector(body_vel, "b", "m/s", 3); } @@ -180,7 +181,6 @@ string LocalCelestialInformation::GetLogHeader() const { string LocalCelestialInformation::GetLogValue() const { string str_tmp = ""; for (int i = 0; i < glo_celes_info_->GetNumBody(); i++) { - //  OUTPUT ONLY POS/VEL LOOKED FROM S/C AT THIS MOMENT for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celes_objects_pos_from_sc_b_[i * 3 + j]); } From 5b62d4c9859a2549a013c77ee0e316db93c8399a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:44:09 +0100 Subject: [PATCH 0035/1086] Fix disturbance log output --- src/Disturbance/AirDrag.cpp | 4 ++-- src/Disturbance/GeoPotential.cpp | 4 ++-- src/Disturbance/GravityGradient.cpp | 2 +- src/Disturbance/MagDisturbance.cpp | 4 ++-- src/Disturbance/ThirdBodyGravity.cpp | 2 +- 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/Disturbance/AirDrag.cpp b/src/Disturbance/AirDrag.cpp index 96c2ac6b9..14f861089 100644 --- a/src/Disturbance/AirDrag.cpp +++ b/src/Disturbance/AirDrag.cpp @@ -87,8 +87,8 @@ void AirDrag::PrintParams(void) // for debug string AirDrag::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteVector("airdrag_torque", "b", "Nm", 3); - str_tmp += WriteVector("airdrag_force", "b", "N", 3); + str_tmp += WriteVector("air_drag_torque", "b", "Nm", 3); + str_tmp += WriteVector("air_drag_force", "b", "N", 3); return str_tmp; } diff --git a/src/Disturbance/GeoPotential.cpp b/src/Disturbance/GeoPotential.cpp index 74bd920d0..9b055d7cc 100644 --- a/src/Disturbance/GeoPotential.cpp +++ b/src/Disturbance/GeoPotential.cpp @@ -13,7 +13,7 @@ #include "../Interface/LogOutput/LogUtility.h" -//#define DEBUG_GEOPOTENTIAL +// #define DEBUG_GEOPOTENTIAL using namespace std; @@ -195,7 +195,7 @@ string GeoPotential::GetLogHeader() const { str_tmp += WriteVector("pos_", "ecef", "m", 3); str_tmp += WriteScalar("time_geop", "ms"); #endif - str_tmp += WriteVector("a_geop", "ecef", "m/s2", 3); + str_tmp += WriteVector("geopotential_acceleration", "ecef", "m/s2", 3); return str_tmp; } diff --git a/src/Disturbance/GravityGradient.cpp b/src/Disturbance/GravityGradient.cpp index 878739e08..43dd83e9a 100644 --- a/src/Disturbance/GravityGradient.cpp +++ b/src/Disturbance/GravityGradient.cpp @@ -36,7 +36,7 @@ Vector<3> GravityGradient::CalcTorque(const Vector<3> r_b_m, const Matrix<3, 3> string GravityGradient::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteVector("ggtorque", "b", "Nm", 3); + str_tmp += WriteVector("gravity_gradient_torque", "b", "Nm", 3); return str_tmp; } diff --git a/src/Disturbance/MagDisturbance.cpp b/src/Disturbance/MagDisturbance.cpp index 45980c6da..2c7fb56c4 100644 --- a/src/Disturbance/MagDisturbance.cpp +++ b/src/Disturbance/MagDisturbance.cpp @@ -56,8 +56,8 @@ void MagDisturbance::PrintTorque() { string MagDisturbance::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteVector("rmm", "b", "Am^2", 3); - str_tmp += WriteVector("mag_dist_torque", "b", "Nm", 3); + str_tmp += WriteVector("spacecraft_magnetic_moment", "b", "Am2", 3); + str_tmp += WriteVector("magnetic_disturbance_torque", "b", "Nm", 3); return str_tmp; } diff --git a/src/Disturbance/ThirdBodyGravity.cpp b/src/Disturbance/ThirdBodyGravity.cpp index 035ea61f8..9690ead46 100644 --- a/src/Disturbance/ThirdBodyGravity.cpp +++ b/src/Disturbance/ThirdBodyGravity.cpp @@ -40,7 +40,7 @@ libra::Vector<3> ThirdBodyGravity::CalcAcceleration(libra::Vector<3> s, libra::V std::string ThirdBodyGravity::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteVector("acc_thirdbody", "i", "m/s2", 3); + str_tmp += WriteVector("third_body_acceleration", "i", "m/s2", 3); return str_tmp; } From d22164b9e239298494696d4a378976b8fce695c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:46:52 +0100 Subject: [PATCH 0036/1086] Fix header information for disturbance plot --- scripts/Plot/common.py | 6 +++--- scripts/Plot/plot_disturbance_force.py | 10 +++++----- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/scripts/Plot/common.py b/scripts/Plot/common.py index 9ae5deb61..b1cb18b48 100644 --- a/scripts/Plot/common.py +++ b/scripts/Plot/common.py @@ -20,9 +20,9 @@ def normalize_csv_read_vector(vector): return np.transpose(normalized_vector) def read_3d_vector_from_csv(read_file_name, header_name, unit): - name_x = header_name + "(X)" + '[' + unit + ']' - name_y = header_name + "(Y)" + '[' + unit + ']' - name_z = header_name + "(Z)" + '[' + unit + ']' + name_x = header_name + "_x" + '[' + unit + ']' + name_y = header_name + "_y" + '[' + unit + ']' + name_z = header_name + "_z" + '[' + unit + ']' csv_data = pandas.read_csv(read_file_name, sep=',', usecols=[name_x, name_y, name_z]) vector = np.array([csv_data[name_x].to_numpy(), csv_data[name_y].to_numpy(), diff --git a/scripts/Plot/plot_disturbance_force.py b/scripts/Plot/plot_disturbance_force.py index 41a83c704..f406ad7b0 100644 --- a/scripts/Plot/plot_disturbance_force.py +++ b/scripts/Plot/plot_disturbance_force.py @@ -46,15 +46,15 @@ # Data read and edit # # Read S2E CSV -time = read_scalar_from_csv(read_file_name, 'time[sec]') +time = read_scalar_from_csv(read_file_name, 'time[s]') srp_force_b = read_3d_vector_from_csv(read_file_name, 'srp_force_b', 'N') -airdrag_force_b = read_3d_vector_from_csv(read_file_name, 'airdrag_force_b', 'N') +airdrag_force_b = read_3d_vector_from_csv(read_file_name, 'air_drag_force_b', 'N') -third_body_acc_i = read_3d_vector_from_csv(read_file_name, 'acc_thirdbody_i', 'm/s2') -geopotential_acc_ecef = read_3d_vector_from_csv(read_file_name, 'a_geop_ecef', 'm/s2') +third_body_acc_i = read_3d_vector_from_csv(read_file_name, 'third_body_acceleration_i', 'm/s2') +geopotential_acc_ecef = read_3d_vector_from_csv(read_file_name, 'geopotential_acceleration_ecef', 'm/s2') -total_acc_i = read_3d_vector_from_csv(read_file_name, 'sat_acc_i_i', 'm/s^2') +total_acc_i = read_3d_vector_from_csv(read_file_name, 'spacecraft_acceleration_i', 'm/s2') # # Plot From cf8c014cb3e4f60e1e03452ca3a2a2233b9401b9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:48:03 +0100 Subject: [PATCH 0037/1086] Fix header information for disturbance torque plot --- scripts/Plot/plot_disturbance_torque.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/scripts/Plot/plot_disturbance_torque.py b/scripts/Plot/plot_disturbance_torque.py index fa05027b3..dc9a923a0 100644 --- a/scripts/Plot/plot_disturbance_torque.py +++ b/scripts/Plot/plot_disturbance_torque.py @@ -46,13 +46,13 @@ # Data read and edit # # Read S2E CSV -time = read_scalar_from_csv(read_file_name, 'time[sec]') +time = read_scalar_from_csv(read_file_name, 'time[s]') -total_torque_b = read_3d_vector_from_csv(read_file_name, 'torque_true_b', 'Nm') -gg_torque_b = read_3d_vector_from_csv(read_file_name, 'ggtorque_b', 'Nm') +total_torque_b = read_3d_vector_from_csv(read_file_name, 'spacecraft_torque_b', 'Nm') +gg_torque_b = read_3d_vector_from_csv(read_file_name, 'gravity_gradient_torque_b', 'Nm') srp_torque_b = read_3d_vector_from_csv(read_file_name, 'srp_torque_b', 'Nm') -airdrag_torque_b = read_3d_vector_from_csv(read_file_name, 'airdrag_torque_b', 'Nm') -mag_torque_b = read_3d_vector_from_csv(read_file_name, 'mag_dist_torque_b', 'Nm') +airdrag_torque_b = read_3d_vector_from_csv(read_file_name, 'air_drag_torque_b', 'Nm') +mag_torque_b = read_3d_vector_from_csv(read_file_name, 'magnetic_disturbance_torque_b', 'Nm') # # Plot From 787e4e8342f34d7b3b67ce697cf3be8e5eecd11a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:53:04 +0100 Subject: [PATCH 0038/1086] Fix body frame plot --- scripts/Plot/plot_body_frame_info.py | 30 ++++++++++------------------ 1 file changed, 10 insertions(+), 20 deletions(-) diff --git a/scripts/Plot/plot_body_frame_info.py b/scripts/Plot/plot_body_frame_info.py index 5e74a2bee..94139d378 100644 --- a/scripts/Plot/plot_body_frame_info.py +++ b/scripts/Plot/plot_body_frame_info.py @@ -15,6 +15,8 @@ # local function from common import find_latest_log_tag from common import normalize_csv_read_vector +from common import read_3d_vector_from_csv + # arguments import argparse @@ -48,32 +50,20 @@ # Data read and edit # # Read S2E CSV for Sun -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['SUN_pos_b(X)[m]', 'SUN_pos_b(Y)[m]', 'SUN_pos_b(Z)[m]']) -sun_position_b = np.transpose(np.array([csv_data['SUN_pos_b(X)[m]'].to_numpy(), - csv_data['SUN_pos_b(Y)[m]'].to_numpy(), - csv_data['SUN_pos_b(Z)[m]'].to_numpy()])) -sun_direction_b = normalize_csv_read_vector(sun_position_b) +sun_position_b = read_3d_vector_from_csv(read_file_name, 'sun_position_from_spacecraft_b', 'm') +sun_direction_b = normalize_csv_read_vector(np.transpose(sun_position_b)) # Read S2E CSV for Earth -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['EARTH_pos_b(X)[m]', 'EARTH_pos_b(Y)[m]', 'EARTH_pos_b(Z)[m]']) -earth_position_b = np.transpose(np.array([csv_data['EARTH_pos_b(X)[m]'].to_numpy(), - csv_data['EARTH_pos_b(Y)[m]'].to_numpy(), - csv_data['EARTH_pos_b(Z)[m]'].to_numpy()])) -earth_direction_b = normalize_csv_read_vector(earth_position_b) +earth_position_b = read_3d_vector_from_csv(read_file_name, 'earth_position_from_spacecraft_b', 'm') +earth_direction_b = normalize_csv_read_vector(np.transpose(earth_position_b)) # Read S2E CSV for Moon -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['MOON_pos_b(X)[m]', 'MOON_pos_b(Y)[m]', 'MOON_pos_b(Z)[m]']) -moon_position_b = np.transpose(np.array([csv_data['MOON_pos_b(X)[m]'].to_numpy(), - csv_data['MOON_pos_b(Y)[m]'].to_numpy(), - csv_data['MOON_pos_b(Z)[m]'].to_numpy()])) -moon_direction_b = normalize_csv_read_vector(moon_position_b) +moon_position_b = read_3d_vector_from_csv(read_file_name, 'moon_position_from_spacecraft_b', 'm') +moon_direction_b = normalize_csv_read_vector(np.transpose(moon_position_b)) # Read S2E CSV for velocity vector -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['sat_velocity_b(X)[m/s]', 'sat_velocity_b(Y)[m/s]', 'sat_velocity_b(Z)[m/s]']) -velocity_vector_b = np.transpose(np.array([csv_data['sat_velocity_b(X)[m/s]'].to_numpy(), - csv_data['sat_velocity_b(Y)[m/s]'].to_numpy(), - csv_data['sat_velocity_b(Z)[m/s]'].to_numpy()])) -velocity_direction_b = normalize_csv_read_vector(velocity_vector_b) +velocity_vector_b = read_3d_vector_from_csv(read_file_name, 'spacecraft_velocity_b', 'm/s') +velocity_direction_b = normalize_csv_read_vector(np.transpose(velocity_vector_b)) # # Plot From 0d1eb9184088d8b94a27c4faf2d3f9ea75f240ad Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 15:54:29 +0100 Subject: [PATCH 0039/1086] Remove unnecessary import --- scripts/Plot/plot_body_frame_info.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/scripts/Plot/plot_body_frame_info.py b/scripts/Plot/plot_body_frame_info.py index 94139d378..e4bf21505 100644 --- a/scripts/Plot/plot_body_frame_info.py +++ b/scripts/Plot/plot_body_frame_info.py @@ -10,8 +10,6 @@ # plots import numpy as np import matplotlib.pyplot as plt -# csv read -import pandas # local function from common import find_latest_log_tag from common import normalize_csv_read_vector From 29c98a7e55abe116e8c6532308f2a141b57ddf22 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:01:37 +0100 Subject: [PATCH 0040/1086] Fix gs visibility plot --- scripts/Plot/plot_gs_visibility.py | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 97dd90c50..525883a9c 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -20,6 +20,7 @@ # local function from make_miller_projection_map import make_miller_projection_map from common import find_latest_log_tag +from common import read_scalar_from_csv # arguments import argparse @@ -66,14 +67,10 @@ # Data read and edit # # Read S2E CSV -df = pandas.read_csv(read_file_name, sep=',', usecols=['lat[rad]', 'lon[rad]', 'is_sc0_visible_from_gs0']) -# satellite position data -sc_lat_deg = df['lat[rad]'].to_numpy() * 180/3.14 -sc_lon_deg = df['lon[rad]'].to_numpy() * 180/3.14 +sc_lat_deg = read_scalar_from_csv(read_file_name, 'spacecraft_latitude[rad]') * 180/3.14 +sc_lon_deg = read_scalar_from_csv(read_file_name, 'spacecraft_longitude[rad]') * 180/3.14 sc_map_lon, sc_map_lat = map(sc_lon_deg, sc_lat_deg) - -# GS visibility data -gs_visibility = df['is_sc0_visible_from_gs0'].to_numpy() +gs_visibility = np.transpose(read_scalar_from_csv(read_file_name, 'is_sc0_visible_from_gs0')) # Set color def visibility_color(visibility): From 1307a355950c23876f71fb2c94c569fb4314b8e5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:02:10 +0100 Subject: [PATCH 0041/1086] Remove unnecessary import --- scripts/Plot/plot_gs_visibility.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 525883a9c..6e05c1e11 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -11,10 +11,7 @@ # # plots import numpy as np -from mpl_toolkits.basemap import Basemap import matplotlib.pyplot as plt -# csv -import pandas # ini file from configparser import ConfigParser # local function From 2e0cbc8cbe0ba7fa0bb46c58e4f9001864c09031 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:06:11 +0100 Subject: [PATCH 0042/1086] Fix orbit plot --- scripts/Plot/plot_orbit_eci.py | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/scripts/Plot/plot_orbit_eci.py b/scripts/Plot/plot_orbit_eci.py index 7669cffa8..63d89e59b 100644 --- a/scripts/Plot/plot_orbit_eci.py +++ b/scripts/Plot/plot_orbit_eci.py @@ -18,6 +18,8 @@ # local function from common import find_latest_log_tag from common import normalize_csv_read_vector +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv # arguments import argparse # math @@ -56,19 +58,13 @@ # Data read and edit # # Read S2E CSV for position -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['sat_position_i(X)[m]', 'sat_position_i(Y)[m]', 'sat_position_i(Z)[m]', 'shadow coefficient']) -sc_position_i = np.array([csv_data['sat_position_i(X)[m]'].to_numpy(), - csv_data['sat_position_i(Y)[m]'].to_numpy(), - csv_data['sat_position_i(Z)[m]'].to_numpy()]) +sc_position_i = read_3d_vector_from_csv(read_file_name, 'spacecraft_position_i', 'm') max_norm_v = max(norm(sc_position_i, axis=0)) -shadow_coeff = csv_data['shadow coefficient'].to_numpy() +shadow_coeff = np.transpose(read_scalar_from_csv(read_file_name, 'shadow_coefficient_at_spacecraft_position')) # Read S2E CSV for Sun -csv_data = pandas.read_csv(read_file_name, sep=',', usecols=['SUN_pos_i(X)[m]', 'SUN_pos_i(Y)[m]', 'SUN_pos_i(Z)[m]']) -sun_position_i = np.transpose(np.array([csv_data['SUN_pos_i(X)[m]'].to_numpy(), - csv_data['SUN_pos_i(Y)[m]'].to_numpy(), - csv_data['SUN_pos_i(Z)[m]'].to_numpy()])) -sun_direction_i = normalize_csv_read_vector(sun_position_i) +sun_position_i = read_3d_vector_from_csv(read_file_name, 'sun_position_i', 'm') +sun_direction_i = normalize_csv_read_vector(np.transpose(sun_position_i)) # # Plot From a3cf0bd173017add1ec7ce0fea662d53bfed1648 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:07:18 +0100 Subject: [PATCH 0043/1086] Fix orbit plot --- scripts/Plot/plot_satellite_orbit_on_miller.py | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/scripts/Plot/plot_satellite_orbit_on_miller.py b/scripts/Plot/plot_satellite_orbit_on_miller.py index 09846bbd5..8933d125b 100644 --- a/scripts/Plot/plot_satellite_orbit_on_miller.py +++ b/scripts/Plot/plot_satellite_orbit_on_miller.py @@ -8,14 +8,11 @@ # Import # # plots -import numpy as np -from mpl_toolkits.basemap import Basemap import matplotlib.pyplot as plt -# csv read -import pandas # local function from make_miller_projection_map import make_miller_projection_map from common import find_latest_log_tag +from common import read_scalar_from_csv # arguments import argparse @@ -55,10 +52,8 @@ # Data read and edit # # Read S2E CSV -df = pandas.read_csv(read_file_name, sep=',', usecols=['lat[rad]', 'lon[rad]']) -# satellite position data -sc_lat_deg = df['lat[rad]'].to_numpy() * 180/3.14 -sc_lon_deg = df['lon[rad]'].to_numpy() * 180/3.14 +sc_lat_deg = read_scalar_from_csv(read_file_name, 'spacecraft_latitude[rad]') * 180/3.14 +sc_lon_deg = read_scalar_from_csv(read_file_name, 'spacecraft_longitude[rad]') * 180/3.14 sc_map_lon, sc_map_lat = map(sc_lon_deg, sc_lat_deg) # From 2b7bfdce1011d50d875bb0c8a79da751b37db4d9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:40:14 +0100 Subject: [PATCH 0044/1086] Fix log output for AOCS components --- src/Component/AOCS/Gyro.cpp | 5 ++--- src/Component/AOCS/MagSensor.cpp | 5 ++--- src/Component/AOCS/MagTorquer.cpp | 7 +++---- src/Component/AOCS/RWModel.cpp | 6 +++--- src/Component/AOCS/STT.cpp | 5 +++-- src/Component/AOCS/SunSensor.cpp | 5 +++-- 6 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/Component/AOCS/Gyro.cpp b/src/Component/AOCS/Gyro.cpp index 55e6b7302..5b93b4544 100644 --- a/src/Component/AOCS/Gyro.cpp +++ b/src/Component/AOCS/Gyro.cpp @@ -27,9 +27,8 @@ void Gyro::MainRoutine(int count) { std::string Gyro::GetLogHeader() const { std::string str_tmp = ""; const std::string st_sensor_id = std::to_string(static_cast(sensor_id_)); - const char* cs = st_sensor_id.data(); - std::string GSection = "gyro_omega"; - str_tmp += WriteVector(GSection + cs, "c", "rad/s", kGyroDim); + std::string sensor_name = "gyro_sensor" + st_sensor_id + "_"; + str_tmp += WriteVector(sensor_name + "measured_angular_velocity", "c", "rad/s", kGyroDim); return str_tmp; } diff --git a/src/Component/AOCS/MagSensor.cpp b/src/Component/AOCS/MagSensor.cpp index daa4b9a4d..8cf5c625a 100644 --- a/src/Component/AOCS/MagSensor.cpp +++ b/src/Component/AOCS/MagSensor.cpp @@ -24,9 +24,8 @@ void MagSensor::MainRoutine(int count) { std::string MagSensor::GetLogHeader() const { std::string str_tmp = ""; const std::string st_sensor_id = std::to_string(static_cast(sensor_id_)); - const char* cs = st_sensor_id.data(); - std::string MSSection = "mag_sensor"; - str_tmp += WriteVector(MSSection + cs, "c", "nT", kMagDim); + std::string sensor_name = "magnetometer" + st_sensor_id + "_"; + str_tmp += WriteVector(sensor_name + "measured_magnetic_field", "c", "nT", kMagDim); return str_tmp; } diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/Component/AOCS/MagTorquer.cpp index 27ccbe6e3..79e33fd12 100644 --- a/src/Component/AOCS/MagTorquer.cpp +++ b/src/Component/AOCS/MagTorquer.cpp @@ -85,11 +85,10 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { std::string MagTorquer::GetLogHeader() const { std::string str_tmp = ""; const std::string st_sensor_id = std::to_string(static_cast(id_)); - const char* cs = st_sensor_id.data(); - std::string MSSection = "mag_torquer"; + std::string actuator_name = "magnetorquer" + st_sensor_id + "_"; - str_tmp += WriteVector(MSSection + cs, "b", "Am^2", kMtqDim); - str_tmp += WriteVector(MSSection + cs, "b", "Nm", kMtqDim); + str_tmp += WriteVector(actuator_name + "output_magnetic_moment", "b", "Am2", kMtqDim); + str_tmp += WriteVector(actuator_name + "output_torque", "b", "Nm", kMtqDim); return str_tmp; } diff --git a/src/Component/AOCS/RWModel.cpp b/src/Component/AOCS/RWModel.cpp index 898c1b8e7..474f0d89b 100644 --- a/src/Component/AOCS/RWModel.cpp +++ b/src/Component/AOCS/RWModel.cpp @@ -182,9 +182,9 @@ std::string RWModel::GetLogHeader() const { std::string str_tmp = ""; str_tmp += WriteScalar("rw_angular_velocity", "rad/s"); - str_tmp += WriteScalar("rw_angular_velocity_rpm", "rpm"); - str_tmp += WriteScalar("rw_angular_velocity_upperlimit", "rpm"); - str_tmp += WriteScalar("rw_angular_acceleration", "rad/s^2"); + str_tmp += WriteScalar("rw_angular_velocity", "rpm"); + str_tmp += WriteScalar("rw_angular_velocity_upper_limit", "rpm"); + str_tmp += WriteScalar("rw_angular_acceleration", "rad/s2"); if (is_logged_jitter_) { str_tmp += WriteVector("rw_jitter_force", "c", "N", 3); diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index e97c8b037..c00727536 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -178,9 +178,10 @@ int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b) { std::string STT::GetLogHeader() const { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(id_)); + std::string sensor_name = "stt" + sensor_id + "_"; - str_tmp += WriteVector("quaternion_STT" + sensor_id, "i2c", "-", 4); - str_tmp += WriteScalar("STT error flag" + sensor_id); + str_tmp += WriteQuaternion(sensor_name + "measured_quaternion", "i2c"); + str_tmp += WriteScalar(sensor_name + "error_flag"); return str_tmp; } diff --git a/src/Component/AOCS/SunSensor.cpp b/src/Component/AOCS/SunSensor.cpp index 863acf730..8ba8b990e 100644 --- a/src/Component/AOCS/SunSensor.cpp +++ b/src/Component/AOCS/SunSensor.cpp @@ -131,9 +131,10 @@ double SunSensor::TanRange(double x) { string SunSensor::GetLogHeader() const { string str_tmp = ""; const string st_id = std::to_string(static_cast(id_)); + std::string sensor_name = "sun_sensor" + st_id + "_"; - str_tmp += WriteVector("sun" + st_id, "c", "-", 3); - str_tmp += WriteScalar("sun_detected_flag" + st_id, "-"); + str_tmp += WriteVector(sensor_name + "measured_sun_direction", "c", "-", 3); + str_tmp += WriteScalar(sensor_name + "sun_detected_flag", "-"); return str_tmp; } From 20b3ab2c37df02698749c792a7c7bcf7325d4cc0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 31 Jan 2023 16:45:54 +0100 Subject: [PATCH 0045/1086] Fix log output for GNSS-R --- src/Component/AOCS/GNSSReceiver.cpp | 29 ++++++++++++++++------------- src/Component/AOCS/GNSSReceiver.h | 2 +- 2 files changed, 17 insertions(+), 14 deletions(-) diff --git a/src/Component/AOCS/GNSSReceiver.cpp b/src/Component/AOCS/GNSSReceiver.cpp index 4b79da210..c06fb11d0 100644 --- a/src/Component/AOCS/GNSSReceiver.cpp +++ b/src/Component/AOCS/GNSSReceiver.cpp @@ -195,19 +195,22 @@ void GNSSReceiver::ConvertJulianDayToGPSTime(const double JulianDay) { std::string GNSSReceiver::GetLogHeader() const // For logs { std::string str_tmp = ""; - str_tmp += WriteScalar("gnss_year"); - str_tmp += WriteScalar("gnss_month"); - str_tmp += WriteScalar("gnss_day"); - str_tmp += WriteScalar("gnss_hour"); - str_tmp += WriteScalar("gnss_min"); - str_tmp += WriteScalar("gnss_sec"); - str_tmp += WriteVector("gnss_position", "eci", "m", 3); - str_tmp += WriteVector("gnss_velocity", "ecef", "m/s", 3); - str_tmp += WriteScalar("gnss_lat", "rad"); - str_tmp += WriteScalar("gnss_lon", "rad"); - str_tmp += WriteScalar("gnss_alt", "m"); - str_tmp += WriteScalar("gnss_vis_flag"); - str_tmp += WriteScalar("gnss_vis_num"); + const std::string sensor_id = std::to_string(static_cast(id_)); + std::string sensor_name = "gnss_receiver" + sensor_id + "_"; + + str_tmp += WriteScalar(sensor_name + "measured_utc_time_year"); + str_tmp += WriteScalar(sensor_name + "measured_utc_time_month"); + str_tmp += WriteScalar(sensor_name + "measured_utc_time_day"); + str_tmp += WriteScalar(sensor_name + "measured_utc_time_hour"); + str_tmp += WriteScalar(sensor_name + "measured_utc_time_min"); + str_tmp += WriteScalar(sensor_name + "measured_utc_time_sec"); + str_tmp += WriteVector(sensor_name + "measured_position", "eci", "m", 3); + str_tmp += WriteVector(sensor_name + "measured_velocity", "ecef", "m/s", 3); + str_tmp += WriteScalar(sensor_name + "measured_latitude", "rad"); + str_tmp += WriteScalar(sensor_name + "measured_longitude", "rad"); + str_tmp += WriteScalar(sensor_name + "measured_altitude", "m"); + str_tmp += WriteScalar(sensor_name + "satellite_visible_flag"); + str_tmp += WriteScalar(sensor_name + "number_of_visible_satellites"); return str_tmp; } diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 4a6c49f46..a89fe5ce1 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -137,7 +137,7 @@ class GNSSReceiver : public ComponentBase, public ILoggable { protected: // Parameters for receiver - const int id_; //!< Receiver ID (not used now) + const int id_; //!< Receiver ID const int ch_max_; //!< Maximum number of channels Vector<3> antenna_position_b_; //!< GNSS antenna position at the body-fixed frame [m] Quaternion q_b2c_; //!< Quaternion from body frame to component frame (antenna frame) From 63b61db378ed91437dc29e678d523246d0be1dbe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 14:39:44 +0100 Subject: [PATCH 0046/1086] Fix log output for components --- src/Component/CommGS/GScalculator.cpp | 5 +++-- .../IdealComponents/ForceGenerator.cpp | 2 +- src/Component/Mission/Telescope/Telescope.cpp | 21 +++++++++++-------- src/Component/Power/BAT.cpp | 5 +++-- src/Component/Power/PCU_InitialStudy.cpp | 5 +++-- src/Component/Power/SAP.cpp | 3 ++- src/Component/Propulsion/SimpleThruster.cpp | 8 +++---- 7 files changed, 28 insertions(+), 21 deletions(-) diff --git a/src/Component/CommGS/GScalculator.cpp b/src/Component/CommGS/GScalculator.cpp index 4657f51a8..16803e6a9 100644 --- a/src/Component/CommGS/GScalculator.cpp +++ b/src/Component/CommGS/GScalculator.cpp @@ -95,9 +95,10 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ std::string GScalculator::GetLogHeader() const { std::string str_tmp = ""; + std::string component_name = "gs_calculator_"; - str_tmp += WriteScalar("max bitrate[Mbps]"); - str_tmp += WriteScalar("receive_margin[dB]"); + str_tmp += WriteScalar(component_name + "max_bitrate", "Mbps"); + str_tmp += WriteScalar(component_name + "receive_margin", "dB"); return str_tmp; } diff --git a/src/Component/IdealComponents/ForceGenerator.cpp b/src/Component/IdealComponents/ForceGenerator.cpp index 1bd42e08b..3e3c11d72 100644 --- a/src/Component/IdealComponents/ForceGenerator.cpp +++ b/src/Component/IdealComponents/ForceGenerator.cpp @@ -64,7 +64,7 @@ void ForceGenerator::SetForce_rtn_N(const libra::Vector<3> force_rtn_N) { std::string ForceGenerator::GetLogHeader() const { std::string str_tmp = ""; - std::string head = "IdealForceGenerator_"; + std::string head = "ideal_force_generator_"; str_tmp += WriteVector(head + "ordered_force", "b", "N", 3); str_tmp += WriteVector(head + "generated_force", "b", "N", 3); str_tmp += WriteVector(head + "generated_force", "i", "N", 3); diff --git a/src/Component/Mission/Telescope/Telescope.cpp b/src/Component/Mission/Telescope/Telescope.cpp index 548a5698c..f72d33c84 100644 --- a/src/Component/Mission/Telescope/Telescope.cpp +++ b/src/Component/Mission/Telescope/Telescope.cpp @@ -150,18 +150,21 @@ void Telescope::ObserveStars() { string Telescope::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteScalar("Sun in forbidden angle", ""); - str_tmp += WriteScalar("Earth in forbidden angle", ""); - str_tmp += WriteScalar("Moon in forbidden angle", ""); - str_tmp += WriteVector("sun_pos_imgsensor", " ", "pix", 2); - str_tmp += WriteVector("earth_pos_imgsensor", " ", "pix", 2); - str_tmp += WriteVector("moon_pos_imgsensor", " ", "pix", 2); + + std::string component_name = "telescope_"; + + str_tmp += WriteScalar(component_name + "sun_in_forbidden_angle", ""); + str_tmp += WriteScalar(component_name + "earth_in_forbidden_angle", ""); + str_tmp += WriteScalar(component_name + "moon_in_forbidden_angle", ""); + str_tmp += WriteVector(component_name + "sun_position", "img", "pix", 2); + str_tmp += WriteVector(component_name + "earth_position", "img", "pix", 2); + str_tmp += WriteVector(component_name + "moon_position", "img", "pix", 2); // When Hipparcos Catalogue was not read, no output of ObserveStars if (hipp_->IsCalcEnabled) { for (size_t i = 0; i < num_of_logged_stars_; i++) { - str_tmp += WriteScalar("HIP ID (" + to_string(i) + ")", " "); - str_tmp += WriteScalar("Vmag (" + to_string(i) + ")", " "); - str_tmp += WriteVector("pos_imagesensor (" + to_string(i) + ")", " ", "pix", 2); + str_tmp += WriteScalar(component_name + "hipparcos_id (" + to_string(i) + ")", " "); + str_tmp += WriteScalar(component_name + "visible_magnitude (" + to_string(i) + ")", " "); + str_tmp += WriteVector(component_name + "star_position (" + to_string(i) + ")", "img", "pix", 2); } } diff --git a/src/Component/Power/BAT.cpp b/src/Component/Power/BAT.cpp index 485b7306a..559b65440 100644 --- a/src/Component/Power/BAT.cpp +++ b/src/Component/Power/BAT.cpp @@ -64,8 +64,9 @@ double BAT::GetCVChargeVoltage() const { return cv_charge_voltage_; } std::string BAT::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("bat_voltage", "V"); - str_tmp += WriteScalar("DoD", "%"); + std::string component_name = "battery_"; + str_tmp += WriteScalar(component_name + "voltage", "V"); + str_tmp += WriteScalar(component_name + "dod", "%"); return str_tmp; } diff --git a/src/Component/Power/PCU_InitialStudy.cpp b/src/Component/Power/PCU_InitialStudy.cpp index d06995b61..c0f1566c8 100644 --- a/src/Component/Power/PCU_InitialStudy.cpp +++ b/src/Component/Power/PCU_InitialStudy.cpp @@ -36,8 +36,9 @@ PCU_InitialStudy::~PCU_InitialStudy() {} std::string PCU_InitialStudy::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("power_consumption", "W"); - str_tmp += WriteScalar("bus_voltage", "V"); + std::string component_name = "pcu_initial_study_"; + str_tmp += WriteScalar(component_name + "power_consumption", "W"); + str_tmp += WriteScalar(component_name + "bus_voltage", "V"); return str_tmp; } diff --git a/src/Component/Power/SAP.cpp b/src/Component/Power/SAP.cpp index 6137c0264..7217cb11d 100644 --- a/src/Component/Power/SAP.cpp +++ b/src/Component/Power/SAP.cpp @@ -78,7 +78,8 @@ void SAP::SetVoltage(const double voltage) { voltage_ = voltage; } std::string SAP::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("power_generation" + std::to_string(id_), "W"); + std::string component_name = "sap" + std::to_string(id_) + "_"; + str_tmp += WriteScalar(component_name + "generated_power", "W"); return str_tmp; } diff --git a/src/Component/Propulsion/SimpleThruster.cpp b/src/Component/Propulsion/SimpleThruster.cpp index dcdecca3f..05b9f46cd 100644 --- a/src/Component/Propulsion/SimpleThruster.cpp +++ b/src/Component/Propulsion/SimpleThruster.cpp @@ -74,10 +74,10 @@ void SimpleThruster::CalcTorque(Vector<3> center) { std::string SimpleThruster::GetLogHeader() const { std::string str_tmp = ""; - std::string head = "TH" + std::to_string(id_); - str_tmp += WriteVector(head + "thrust", "b", "N", 3); - str_tmp += WriteVector(head + "torque", "b", "Nm", 3); - str_tmp += WriteScalar(head + "thrust", "N"); + std::string head = "simple_thruster" + std::to_string(id_) + "_"; + str_tmp += WriteVector(head + "output_thrust", "b", "N", 3); + str_tmp += WriteVector(head + "output_torque", "b", "Nm", 3); + str_tmp += WriteScalar(head + "output_thrust_norm", "N"); return str_tmp; } From dff7c7517abe3c65099a901f94845dca0dee11a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 14:43:12 +0100 Subject: [PATCH 0047/1086] Fix log output for ground station --- src/Simulation/GroundStation/GroundStation.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/Simulation/GroundStation/GroundStation.cpp b/src/Simulation/GroundStation/GroundStation.cpp index 12cde16b6..3b28d0e74 100644 --- a/src/Simulation/GroundStation/GroundStation.cpp +++ b/src/Simulation/GroundStation/GroundStation.cpp @@ -73,8 +73,9 @@ bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { std::string GroundStation::GetLogHeader() const { std::string str_tmp = ""; + std::string head = "ground_station" + std::to_string(gs_id_) + "_"; for (int i = 0; i < num_sc_; i++) { - std::string legend = "is_sc" + std::to_string(i) + "_visible_from_gs" + std::to_string(gs_id_); + std::string legend = head + "sc" + std::to_string(i) + "_visible_flag"; str_tmp += WriteScalar(legend); } return str_tmp; From 15b022ccac33c88d68ddae2fec76178c5e35cbec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 14:44:25 +0100 Subject: [PATCH 0048/1086] Fix gs_visible plot script --- scripts/Plot/plot_gs_visibility.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 6e05c1e11..546435b9a 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -67,7 +67,7 @@ sc_lat_deg = read_scalar_from_csv(read_file_name, 'spacecraft_latitude[rad]') * 180/3.14 sc_lon_deg = read_scalar_from_csv(read_file_name, 'spacecraft_longitude[rad]') * 180/3.14 sc_map_lon, sc_map_lat = map(sc_lon_deg, sc_lat_deg) -gs_visibility = np.transpose(read_scalar_from_csv(read_file_name, 'is_sc0_visible_from_gs0')) +gs_visibility = np.transpose(read_scalar_from_csv(read_file_name, 'ground_station0_sc0_visible_flag')) # Set color def visibility_color(visibility): From 4205b80eca31724899d022a520b5a1b00a744662 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 14:46:40 +0100 Subject: [PATCH 0049/1086] Fix typo --- scripts/Plot/plot_gs_visibility.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 546435b9a..8f3bffd48 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -86,7 +86,7 @@ def visibility_color(visibility): for i in range(len(sc_map_lat)): map.plot(sc_map_lon[i], sc_map_lat[i], color=visibility_color(gs_visibility[i]), marker='o', markersize=3) -plt.title('GS Visilibity Analysis: logs_' + read_file_tag) +plt.title('GS Visibility Analysis: logs_' + read_file_tag) if args.no_gui: plt.savefig(read_file_tag + "_gs_visibility.png") From b89daff19b81377941a8b11c729bf15fcf02de53 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 15:13:12 +0100 Subject: [PATCH 0050/1086] Add absolute time into log output --- src/Environment/Global/SimTime.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/Environment/Global/SimTime.cpp b/src/Environment/Global/SimTime.cpp index 4dccca830..3c631ce79 100644 --- a/src/Environment/Global/SimTime.cpp +++ b/src/Environment/Global/SimTime.cpp @@ -193,7 +193,8 @@ void SimTime::PrintStartDateTime(void) const { string SimTime::GetLogHeader() const { string str_tmp = ""; - str_tmp += WriteScalar("time", "s"); + str_tmp += WriteScalar("elapsed_time", "s"); + str_tmp += WriteScalar("time", "UTC"); return str_tmp; } @@ -203,6 +204,12 @@ string SimTime::GetLogValue() const { str_tmp += WriteScalar(elapsed_time_sec_); + const char kSize = 100; + char ymdhms[kSize]; + snprintf(ymdhms, kSize, "%4d/%02d/%02d %02d:%02d:%.3lf", current_utc_.year, current_utc_.month, current_utc_.day, current_utc_.hour, + current_utc_.min, current_utc_.sec); + str_tmp += ymdhms; + return str_tmp; } From 91911e64d0ef2b81300c96dca53391b4a200b001 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 15:52:29 +0100 Subject: [PATCH 0051/1086] Fix ini file for structure --- data/SampleSat/ini/SampleStructure.ini | 130 +++++++++--------- .../Spacecraft/Structure/InitStructure.cpp | 22 +-- 2 files changed, 76 insertions(+), 76 deletions(-) diff --git a/data/SampleSat/ini/SampleStructure.ini b/data/SampleSat/ini/SampleStructure.ini index 7d64810d2..11722eb8f 100644 --- a/data/SampleSat/ini/SampleStructure.ini +++ b/data/SampleSat/ini/SampleStructure.ini @@ -7,73 +7,73 @@ [STRUCTURE] // Inertia Tensor @ body fixed frame [kg・m2] -Iner(0) = 0.1 //I(0,0) -Iner(1) = 0.0 //I(0,1) -Iner(2) = 0.0 //I(0,2) -Iner(3) = 0.0 //I(1,0) -Iner(4) = 0.1 //I(1,1) -Iner(5) = 0.0 //I(1,2) -Iner(6) = 0.0 //I(2,0) -Iner(7) = 0.0 //I(2,1) -Iner(8) = 0.1 //I(2,2) +inertia_tensor_kgm2(0) = 0.1 // I_xx +inertia_tensor_kgm2(1) = 0.0 // I_xy +inertia_tensor_kgm2(2) = 0.0 // I_xz +inertia_tensor_kgm2(3) = 0.0 // I_yx +inertia_tensor_kgm2(4) = 0.1 // I_yy +inertia_tensor_kgm2(5) = 0.0 // I_yz +inertia_tensor_kgm2(6) = 0.0 // I_zx +inertia_tensor_kgm2(7) = 0.0 // I_zy +inertia_tensor_kgm2(8) = 0.1 // I_zz -mass = 14 //[kg] +mass_kg = 14 // Position vector of the center of gravity @ the body frame [m] -cg_b(0) = 0.01 -cg_b(1) = 0.01 -cg_b(2) = 0.01 +center_of_gravity_b_m(0) = 0.01 +center_of_gravity_b_m(1) = 0.01 +center_of_gravity_b_m(2) = 0.01 [SURFACES] -num_of_surfaces = 6 +number_of_surfaces = 6 // Area of each surface [m^2] -area_0 = 0.25 -area_1 = 0.25 -area_2 = 0.25 -area_3 = 0.25 -area_4 = 0.25 -area_5 = 0.25 +area_0_m2 = 0.25 +area_1_m2 = 0.25 +area_2_m2 = 0.25 +area_3_m2 = 0.25 +area_4_m2 = 0.25 +area_5_m2 = 0.25 // Position vector of each surface geometric center @ body frame [m] -position_0(0) = 0.25 -position_0(1) = 0.0 -position_0(2) = 0.0 -position_1(0) = -0.25 -position_1(1) = 0.0 -position_1(2) = 0.0 -position_2(0) = 0.0 -position_2(1) = 0.25 -position_2(2) = 0.0 -position_3(0) = 0.0 -position_3(1) = -0.25 -position_3(2) = 0.0 -position_4(0) = 0.0 -position_4(1) = 0.0 -position_4(2) = 0.25 -position_5(0) = 0.0 -position_5(1) = 0.0 -position_5(2) = -0.25 +position_0_b_m(0) = 0.25 +position_0_b_m(1) = 0.0 +position_0_b_m(2) = 0.0 +position_1_b_m(0) = -0.25 +position_1_b_m(1) = 0.0 +position_1_b_m(2) = 0.0 +position_2_b_m(0) = 0.0 +position_2_b_m(1) = 0.25 +position_2_b_m(2) = 0.0 +position_3_b_m(0) = 0.0 +position_3_b_m(1) = -0.25 +position_3_b_m(2) = 0.0 +position_4_b_m(0) = 0.0 +position_4_b_m(1) = 0.0 +position_4_b_m(2) = 0.25 +position_5_b_m(0) = 0.0 +position_5_b_m(1) = 0.0 +position_5_b_m(2) = -0.25 // Normal vector of each surface @ body frame -normal_0(0) = 1.0 -normal_0(1) = 0.0 -normal_0(2) = 0.0 -normal_1(0) = -1.0 -normal_1(1) = 0.0 -normal_1(2) = 0.0 -normal_2(0) = 0.0 -normal_2(1) = 1.0 -normal_2(2) = 0.0 -normal_3(0) = 0.0 -normal_3(1) = -1.0 -normal_3(2) = 0.0 -normal_4(0) = 0.0 -normal_4(1) = 0.0 -normal_4(2) = 1.0 -normal_5(0) = 0.0 -normal_5(1) = 0.0 -normal_5(2) = -1.0 +normal_vector_0_b(0) = 1.0 +normal_vector_0_b(1) = 0.0 +normal_vector_0_b(2) = 0.0 +normal_vector_1_b(0) = -1.0 +normal_vector_1_b(1) = 0.0 +normal_vector_1_b(2) = 0.0 +normal_vector_2_b(0) = 0.0 +normal_vector_2_b(1) = 1.0 +normal_vector_2_b(2) = 0.0 +normal_vector_3_b(0) = 0.0 +normal_vector_3_b(1) = -1.0 +normal_vector_3_b(2) = 0.0 +normal_vector_4_b(0) = 0.0 +normal_vector_4_b(1) = 0.0 +normal_vector_4_b(2) = 1.0 +normal_vector_5_b(0) = 0.0 +normal_vector_5_b(1) = 0.0 +normal_vector_5_b(2) = -1.0 // Total reflectance for the Sun spectrum reflectivity_0 = 0.4 @@ -101,15 +101,15 @@ air_specularity_5 = 0.4 [RMM] // Constant component of Residual Magnetic Moment(RMM) [A・m^2] -rmm_const_b(0) = 0.04 -rmm_const_b(1) = 0.04 -rmm_const_b(2) = 0.04 +rmm_constant_b_Am2(0) = 0.04 +rmm_constant_b_Am2(1) = 0.04 +rmm_constant_b_Am2(2) = 0.04 -// RMM Random Walk Speed [nT] -rmm_rwdev = 1.0E-5 +// RMM Random Walk Speed [A・m^2] +rmm_random_walk_speed_Am2 = 1.0E-5 -// RMM Random Walk Limit [nT] -rmm_rwlimit = 1.0E-3 +// RMM Random Walk Limit [A・m^2] +rmm_random_walk_limit_Am2 = 1.0E-3 -// RMM White Noise Standard deviation [nT] -rmm_wnvar = 5.0E-5 +// RMM White Noise Standard deviation [A・m^2] +rmm_white_noise_standard_deviation_Am2 = 5.0E-5 diff --git a/src/Simulation/Spacecraft/Structure/InitStructure.cpp b/src/Simulation/Spacecraft/Structure/InitStructure.cpp index 253de4fc1..77d348653 100644 --- a/src/Simulation/Spacecraft/Structure/InitStructure.cpp +++ b/src/Simulation/Spacecraft/Structure/InitStructure.cpp @@ -15,11 +15,11 @@ KinematicsParams InitKinematicsParams(std::string ini_path) { const char* section = "STRUCTURE"; Vector<3> cg_b; - conf.ReadVector(section, "cg_b", cg_b); - double mass = conf.ReadDouble(section, "mass"); + conf.ReadVector(section, "center_of_gravity_b_m", cg_b); + double mass = conf.ReadDouble(section, "mass_kg"); Vector<9> inertia_vec; Matrix<3, 3> inertia_tensor; - conf.ReadVector(section, "Iner", inertia_vec); + conf.ReadVector(section, "inertia_tensor_kgm2", inertia_vec); for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { inertia_tensor[i][j] = inertia_vec[i * 3 + j]; @@ -36,7 +36,7 @@ vector InitSurfaces(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "SURFACES"; - const int num_surface = conf.ReadInt(section, "num_of_surfaces"); + const int num_surface = conf.ReadInt(section, "number_of_surfaces"); vector surfaces; for (int i = 0; i < num_surface; i++) { @@ -44,7 +44,7 @@ vector InitSurfaces(std::string ini_path) { idx = "_" + idx; std::string keyword; - keyword = "area" + idx; + keyword = "area" + idx + "_m2"; double area = conf.ReadDouble(section, keyword.c_str()); if (area < -MIN_VAL) // Fixme: magic word { @@ -89,10 +89,10 @@ vector InitSurfaces(std::string ini_path) { } Vector<3> position, normal; - keyword = "position" + idx; + keyword = "position" + idx + "_b_m"; conf.ReadVector(section, keyword.c_str(), position); - keyword = "normal" + idx; + keyword = "normal_vector" + idx + "_b"; conf.ReadVector(section, keyword.c_str(), normal); if (norm(normal) > 1.0 + MIN_VAL) // Fixme: magic word { @@ -112,10 +112,10 @@ RMMParams InitRMMParams(std::string ini_path) { const char* section = "RMM"; Vector<3> rmm_const_b; - conf.ReadVector(section, "rmm_const_b", rmm_const_b); - double rmm_rwdev = conf.ReadDouble(section, "rmm_rwdev"); - double rmm_rwlimit = conf.ReadDouble(section, "rmm_rwlimit"); - double rmm_wnvar = conf.ReadDouble(section, "rmm_wnvar"); + conf.ReadVector(section, "rmm_constant_b_Am2", rmm_const_b); + double rmm_rwdev = conf.ReadDouble(section, "rmm_random_walk_speed_Am2"); + double rmm_rwlimit = conf.ReadDouble(section, "rmm_random_walk_limit_Am2"); + double rmm_wnvar = conf.ReadDouble(section, "rmm_white_noise_standard_deviation_Am2"); RMMParams rmm_params(rmm_const_b, rmm_rwdev, rmm_rwlimit, rmm_wnvar); return rmm_params; From edf5b4e19b6584ecc9caff3363b87d260b5bcae6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 16:00:18 +0100 Subject: [PATCH 0052/1086] Fix ini file for local environment --- data/SampleSat/ini/SampleLocalEnvironment.ini | 18 +++++++++--------- src/Environment/Local/InitLocalEnvironment.cpp | 14 +++++++------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/data/SampleSat/ini/SampleLocalEnvironment.ini b/data/SampleSat/ini/SampleLocalEnvironment.ini index 22944d49e..260eac7ee 100644 --- a/data/SampleSat/ini/SampleLocalEnvironment.ini +++ b/data/SampleSat/ini/SampleLocalEnvironment.ini @@ -1,10 +1,10 @@ [MAG_ENVIRONMENT] calculation = ENABLE logging = ENABLE -coeff_file = ../../../s2e-core/src/Library/igrf/igrf13.coef -mag_rwdev = 10.0 //Random Walk speed[nT] -mag_rwlimit = 400.0 //Random Walk max limit[nT] -mag_wnvar = 50.0 //White noise standard deviation [nT] +coefficient_file = ../../../s2e-core/src/Library/igrf/igrf13.coef +magnetic_field_random_walk_speed_nT = 10.0 +magnetic_field_random_walk_limit_nT = 400.0 +magnetic_field_white_noise_standard_deviation_nT = 50.0 [SRP] @@ -19,15 +19,15 @@ logging = ENABLE // Atmosphere model // STANDARD: Model using scale height, NRLMSISE00: NRLMSISE00 model model = STANDARD -nrlmsise00_table_path = ../../../ExtLibraries/nrlmsise00/table/SpaceWeather.txt +nrlmsise00_table_file = ../../../ExtLibraries/nrlmsise00/table/SpaceWeather.txt // Whether using user-defined f10.7 and ap value // Ref of f10.7: https://www.swpc.noaa.gov/phenomena/f107-cm-radio-emissions // Ref of ap: http://wdc.kugi.kyoto-u.ac.jp/kp/kpexp-j.html -is_manual_param_used = ENABLE -manual_daily_f107 = 150.0 // User defined f10.7(1 day) -manual_average_f107 = 150.0 // User defined f10.7(30 days average) +is_manual_parameter_used = ENABLE +manual_daily_f107 = 150.0 // User defined f10.7 (1 day) +manual_average_f107 = 150.0 // User defined f10.7 (30 days average) manual_ap = 3.0 // User defined ap -rho_stddev = 0.0 // Standard deviation of the air density +air_density_standard_deviation = 0.0 // Standard deviation of the air density [LOCAL_CELESTIAL_INFORMATION] diff --git a/src/Environment/Local/InitLocalEnvironment.cpp b/src/Environment/Local/InitLocalEnvironment.cpp index 1245a3834..9bb1d5bd2 100644 --- a/src/Environment/Local/InitLocalEnvironment.cpp +++ b/src/Environment/Local/InitLocalEnvironment.cpp @@ -16,10 +16,10 @@ MagEnvironment InitMagEnvironment(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "MAG_ENVIRONMENT"; - std::string fname = conf.ReadString(section, "coeff_file"); - double mag_rwdev = conf.ReadDouble(section, "mag_rwdev"); - double mag_rwlimit = conf.ReadDouble(section, "mag_rwlimit"); - double mag_wnvar = conf.ReadDouble(section, "mag_wnvar"); + std::string fname = conf.ReadString(section, "coefficient_file"); + double mag_rwdev = conf.ReadDouble(section, "magnetic_field_random_walk_speed_nT"); + double mag_rwlimit = conf.ReadDouble(section, "magnetic_field_random_walk_limit_nT"); + double mag_wnvar = conf.ReadDouble(section, "magnetic_field_white_noise_standard_deviation_nT"); MagEnvironment mag_env(fname, mag_rwdev, mag_rwlimit, mag_wnvar); mag_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); @@ -46,9 +46,9 @@ Atmosphere InitAtmosphere(std::string ini_path) { double f107_default = 150.0; std::string model = conf.ReadString(section, "model"); - std::string table_path = conf.ReadString(section, "nrlmsise00_table_path"); - double rho_stddev = conf.ReadDouble(section, "rho_stddev"); - bool is_manual_param_used = conf.ReadEnable(section, "is_manual_param_used"); + std::string table_path = conf.ReadString(section, "nrlmsise00_table_file"); + double rho_stddev = conf.ReadDouble(section, "air_density_standard_deviation"); + bool is_manual_param_used = conf.ReadEnable(section, "is_manual_parameter_used"); double manual_daily_f107 = conf.ReadDouble(section, "manual_daily_f107"); if (manual_daily_f107 < f107_threshold) { std::cerr << "Daily F10.7 may be too low. It is set as 150.0 in this simulation. " From c007f5de032bb24c3040b79cb0f9f92ad80f81e4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 16:10:32 +0100 Subject: [PATCH 0053/1086] Fix ini file for disturbances --- data/SampleSat/ini/SampleDisturbance.ini | 20 +++++++++----------- src/Disturbance/InitDisturbance.cpp | 18 +++++++++--------- 2 files changed, 18 insertions(+), 20 deletions(-) diff --git a/data/SampleSat/ini/SampleDisturbance.ini b/data/SampleSat/ini/SampleDisturbance.ini index 0e8e2f0ad..afd4212a4 100644 --- a/data/SampleSat/ini/SampleDisturbance.ini +++ b/data/SampleSat/ini/SampleDisturbance.ini @@ -3,7 +3,7 @@ calculation = DISABLE logging = ENABLE degree = 4 -file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii +coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii [MAG_DISTURBANCE] @@ -18,11 +18,9 @@ calculation = ENABLE logging = ENABLE // Condition of air drag -Temp_wall = 30 // Surface Temperature[degC] -Temp_molecular = 3 // Atmosphere Temperature[degC] - -// Note: they are converted in unit [K] inside the codes -Molecular = 18.0 // Molecular weight of the thermosphere[g/mol] +wall_temperature_degC = 30 // Surface Temperature[degC] +molecular_temperature_degC = 3 // Atmosphere Temperature[degC] +molecular_weight = 18.0 // Molecular weight of the thermosphere[g/mol] [SRDIST] @@ -40,10 +38,10 @@ calculation = DISABLE logging = ENABLE // The number of gravity-generating bodies other than the central body -num_of_third_body = 1 +number_of_third_body = 1 // List of gravity-generating bodies other than the central body -// All these bodies must be included in the "selected_body" of "[PLANET_SELECTION]" -third_body(0) = SUN -third_body(1) = MOON -third_body(2) = MARS +// All these bodies must be included in the "selected_body_name" of "[CelestialInformation]" +third_body_name(0) = SUN +third_body_name(1) = MOON +third_body_name(2) = MARS diff --git a/src/Disturbance/InitDisturbance.cpp b/src/Disturbance/InitDisturbance.cpp index 700c4f431..22429b515 100644 --- a/src/Disturbance/InitDisturbance.cpp +++ b/src/Disturbance/InitDisturbance.cpp @@ -15,9 +15,9 @@ AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, auto conf = IniAccess(ini_path); const char* section = "AIRDRAG"; - double t_w = conf.ReadDouble(section, "Temp_wall") + 273.0; - double t_m = conf.ReadDouble(section, "Temp_molecular") + 273.0; - double molecular = conf.ReadDouble(section, "Molecular"); + double t_w = conf.ReadDouble(section, "wall_temperature_degC") + 273.0; + double t_m = conf.ReadDouble(section, "molecular_temperature_degC") + 273.0; + double molecular = conf.ReadDouble(section, "molecular_weight"); bool calcen = conf.ReadEnable(section, CALC_LABEL); bool logen = conf.ReadEnable(section, LOG_LABEL); @@ -81,7 +81,7 @@ GeoPotential InitGeoPotential(std::string ini_path) { const char* section = "GEOPOTENTIAL"; int degree = conf.ReadInt(section, "degree"); - std::string file_path = conf.ReadString(section, "file_path"); + std::string file_path = conf.ReadString(section, "coefficients_file_path"); GeoPotential geop(degree, file_path); geop.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); geop.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); @@ -92,13 +92,13 @@ GeoPotential InitGeoPotential(std::string ini_path) { ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes) { // Generate a list of bodies to be calculated in "CelesInfo" auto conf_celes = IniAccess(ini_path_celes); - const char* section_celes = "PLANET_SELECTION"; - const int num_of_selected_body = conf_celes.ReadInt(section_celes, "num_of_selected_body"); + const char* section_celes = "CelestialInformation"; + const int num_of_selected_body = conf_celes.ReadInt(section_celes, "number_of_selected_body"); std::string center_object = conf_celes.ReadString(section_celes, "center_object"); std::set selected_body_list; for (int i = 0; i < num_of_selected_body; i++) { - std::string selected_body_id = "selected_body(" + std::to_string(i) + ")"; + std::string selected_body_id = "selected_body_name(" + std::to_string(i) + ")"; selected_body_list.insert(conf_celes.ReadString(section_celes, selected_body_id.c_str())); } @@ -106,13 +106,13 @@ ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path auto conf = IniAccess(ini_path); const char* section = "THIRD_BODY_GRAVITY"; - const int num_of_third_body = conf.ReadInt(section, "num_of_third_body"); + const int num_of_third_body = conf.ReadInt(section, "number_of_third_body"); std::set third_body_list; // Generate the list of the third object if "calculation=ENABLE" if (conf.ReadEnable(section, CALC_LABEL)) { for (int i = 0; i < num_of_third_body; i++) { - std::string third_body_id = "third_body(" + std::to_string(i) + ")"; + std::string third_body_id = "third_body_name(" + std::to_string(i) + ")"; std::string third_body_name = conf.ReadString(section, third_body_id.c_str()); // If the object specified by `third_body` in "SampleDisturbance.ini" is // the center object of the orbital propagation, the system prints an From 1cbedcbad0d87242158b9f03ff6571644cf47bfd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 16:50:59 +0100 Subject: [PATCH 0054/1086] Fix ini file for satellite --- data/SampleSat/ini/SampleSat.ini | 131 +++++++++------------ src/Disturbance/Disturbances.cpp | 2 +- src/Dynamics/Attitude/InitAttitude.cpp | 20 ++-- src/Dynamics/Orbit/InitOrbit.cpp | 31 ++--- src/Dynamics/Thermal/InitTemperature.cpp | 4 +- src/Environment/Local/LocalEnvironment.cpp | 2 +- 6 files changed, 85 insertions(+), 105 deletions(-) diff --git a/data/SampleSat/ini/SampleSat.ini b/data/SampleSat/ini/SampleSat.ini index f6f0cafc6..9a5d2efdb 100644 --- a/data/SampleSat/ini/SampleSat.ini +++ b/data/SampleSat/ini/SampleSat.ini @@ -4,23 +4,23 @@ // CONTROLLED : Attitude Calculation with Controlled Attitude mode. All disturbances and control torque are ignored. propagate_mode = RK4 -// Initial angular velocity at body frame,[rad/s] -Omega_b(0) = 0.0 -Omega_b(1) = 0.0 -Omega_b(2) = 0.0 +// Initial angular velocity at body frame [rad/s] +initial_angular_velocity_b_rad_s(0) = 0.0 +initial_angular_velocity_b_rad_s(1) = 0.0 +initial_angular_velocity_b_rad_s(2) = 0.0 -// Initial quaternion,i->b,(real part,imaginary part) +// Initial quaternion inertial frame to body frame (real part, imaginary part) // This value also used in INERTIAL_STABILIZE mode of ControlledAttitude -Quaternion_i2b(0) = 0.0 -Quaternion_i2b(1) = 0.0 -Quaternion_i2b(2) = 0.0 -Quaternion_i2b(3) = 1.0 +initial_quaternion_i2b(0) = 0.0 +initial_quaternion_i2b(1) = 0.0 +initial_quaternion_i2b(2) = 0.0 +initial_quaternion_i2b(3) = 1.0 -// Initial torque at body frame,[Nm] +// Initial torque at body frame [Nm] // Note: The initial torque added just for the first propagation step -Torque_b(0) = +0.000 -Torque_b(1) = -0.000 -Torque_b(2) = 0.000 +initial_torque_b_Nm(0) = +0.000 +initial_torque_b_Nm(1) = -0.000 +initial_torque_b_Nm(2) = 0.000 [ControlledAttitude] // Mode definitions @@ -33,15 +33,15 @@ main_mode = INERTIAL_STABILIZE sub_mode = SUN_POINTING // Pointing direction @ body frame for main pointing mode -pointing_t_b(0) = 1.0 -pointing_t_b(1) = 0.0 -pointing_t_b(2) = 0.0 +main_pointing_direction_b(0) = 1.0 +main_pointing_direction_b(1) = 0.0 +main_pointing_direction_b(2) = 0.0 // Pointing direction @ body frame for sub pointing mode -// pointing_t_b and pointing_sub_t_b should separate larger than 30 degrees. -pointing_sub_t_b(0) = 0.0 -pointing_sub_t_b(1) = 0.0 -pointing_sub_t_b(2) = 1.0 +// main_pointing_direction_b and sub_pointing_direction_b should separate larger than 30 degrees. +sub_pointing_direction_b(0) = 0.0 +sub_pointing_direction_b(1) = 0.0 +sub_pointing_direction_b(2) = 1.0 [ORBIT] calculation = ENABLE @@ -53,13 +53,33 @@ logging = ENABLE // RELATIVE : Relative dynamics (for formation flying simulation) // KEPLER : Kepler orbit propagation without disturbances and thruster maneuver // ENCKE : Encke orbit propagation with disturbances and thruster maneuver -propagate_mode = SGP4 +propagate_mode = RK4 // Orbit initialize mode for RK4, KEPLER, and ENCKE // DEFAULT : Use default initialize method (RK4 and ENCKE use pos/vel, KEPLER uses init_mode_kepler) // POSITION_VELOCITY_I : Initialize with position and velocity in the inertial frame // ORBITAL_ELEMENTS : Initialize with orbital elements -initialize_mode = ORBITAL_ELEMENTS +initialize_mode = POSITION_VELOCITY_I + +// Initial value definition for POSITION_VELOCITY_I initialize mode //////// +initial_position_i_m(0) = -2111769.7723711144 +initial_position_i_m(1) = -5360353.2254375768 +initial_position_i_m(2) = 3596181.6497774957 + +initial_velocity_i_m_s(0) = 4200.4344740455268 +initial_velocity_i_m_s(1) = -4637.540129059361 +initial_velocity_i_m_s(2) = -4429.2361258448807 +/////////////////////////////////////////////////////////////////////////// + +// Initial value definition for ORBITAL_ELEMENTS initialize mode //////// +semi_major_axis_m = 6794500.0 +eccentricity = 0.0015 +inclination_rad = 0.9012 +raan_rad = 0.1411 +argument_of_perigee_rad = 1.7952 +epoch_jday = 2.458940966402607e6 +/////////////////////////////////////////////////////////////////////////////// + // Settings for SGP4 /////////////////////////////////////////////// // TLE @@ -70,23 +90,7 @@ tle2=2 25544 51.6412 86.9962 0006063 30.9353 329.2153 15.49228202 17647 wgs = 2 // 0: wgs72old, 1: wgs72, 2: wgs84 ////////////////////////////////////////////////////////////////////////// -// Initial value definition for RK4 ////////////////////////////////////// -// * The coordinate system is defined at [PLANET_SELECTION] in SampleSimBase.ini -// Initial satellite position[m] -// Example: ISS -init_position(0) = -2111769.7723711144 -init_position(1) = -5360353.2254375768 -init_position(2) = 3596181.6497774957 - -// Initial satellite velocity[m/s] -// Example: ISS -init_velocity(0) = 4200.4344740455268 -init_velocity(1) = -4637.540129059361 -init_velocity(2) = -4429.2361258448807 -/////////////////////////////////////////////////////////////////////////// - - -// Information used for relative orbit propagation////////////////////////////// +// Settings for relative orbit propagation //////////////////////////// // Relative Orbit Update Method (0 means RK4, 1 means STM) relative_orbit_update_method = 0 // RK4 Relative Dynamics model type (only valid for RK4 update) @@ -97,52 +101,33 @@ relative_dynamics_model_type = 0 stm_model_type = 0 // Initial satellite position relative to the reference satellite in LVLH frame[m] // * The coordinate system is defined at [PLANET_SELECTION] in SampleSimBase.ini -init_relative_position_lvlh(0) = 0.0 -init_relative_position_lvlh(1) = 100.0 -init_relative_position_lvlh(2) = 0.0 +initial_relative_position_lvlh_m(0) = 0.0 +initial_relative_position_lvlh_m(1) = 100.0 +initial_relative_position_lvlh_m(2) = 0.0 // initial satellite velocity relative to the reference satellite in LVLH frame[m/s] -init_relative_velocity_lvlh(0) = 0.0 -init_relative_velocity_lvlh(1) = 0.0 -init_relative_velocity_lvlh(2) = 0.0 +initial_relative_velocity_lvlh_m_s(0) = 0.0 +initial_relative_velocity_lvlh_m_s(1) = 0.0 +initial_relative_velocity_lvlh_m_s(2) = 0.0 // information of reference satellite -reference_sat_id = 1 -/////////////////////////////////////////////////////////////////////////////// - - -// Information used for orbital propagation by the Kepler Motion /////////// -// initialize mode for kepler motion. -// WARNINGS: init_mode_kepler will be integrated with initialize_mode mentioned above -// The initialize_mode has higher priority than init_mode_kepler -// INIT_POSVEL : initialize with position and velocity defined for RK4 -// INIT_OE : initialize with the following orbital elements -init_mode_kepler = INIT_OE -// Orbital Elements for INIT_OE -semi_major_axis_m = 6794500.0 -eccentricity = 0.0015 -inclination_rad = 0.9012 -raan_rad = 0.1411 -arg_perigee_rad = 1.7952 -epoch_jday = 2.458940966402607e6 +reference_satellite_id = 1 /////////////////////////////////////////////////////////////////////////////// - -// Information used for orbital propagation by the Encke Formulation /////////// +// Settings for Encke mode /////////// error_tolerance = 0.0001 -// initialize position and vector are same with RK4 setting /////////////////////////////////////////////////////////////////////////////// [Thermal] -IsCalcEnabled=0 -debug=0 -thrm_file = ../../data/SampleSat/ini/Thermal_CSV/ +calculation = DISABLE +debug = 0 +thermal_file_directory = ../../data/SampleSat/ini/Thermal_CSV/ [LOCAL_ENVIRONMENT] -local_env_file = ../../data/SampleSat/ini/SampleLocalEnvironment.ini +local_environment_file = ../../data/SampleSat/ini/SampleLocalEnvironment.ini [DISTURBANCE] -dist_file = ../../data/SampleSat/ini/SampleDisturbance.ini +disturbance_file = ../../data/SampleSat/ini/SampleDisturbance.ini [STRUCTURE_FILE] @@ -151,11 +136,11 @@ structure_file = ../../data/SampleSat/ini/SampleStructure.ini [COMPONENTS_FILE] gyro_file = ../../data/SampleSat/ini/component/gyro.ini -mag_sensor_file = ../../data/SampleSat/ini/component/magsensor.ini +magetometer_file = ../../data/SampleSat/ini/component/magsensor.ini stt_file = ../../data/SampleSat/ini/component/STT.ini ss_file = ../../data/SampleSat/ini/component/SS.ini gnss_file = ../../data/SampleSat/ini/component/GNSSReceiver.ini -mag_torquer_file = ../../data/SampleSat/ini/component/magtorquer.ini +magetorquer_file = ../../data/SampleSat/ini/component/magtorquer.ini rw_file = ../../data/SampleSat/ini/component/RW.ini thruster_file = ../../data/SampleSat/ini/component/Thruster.ini force_generator_file = ../../data/SampleSat/ini/component/ForceGenerator.ini diff --git a/src/Disturbance/Disturbances.cpp b/src/Disturbance/Disturbances.cpp index 818fe2810..6ca48fb6b 100644 --- a/src/Disturbance/Disturbances.cpp +++ b/src/Disturbance/Disturbances.cpp @@ -71,7 +71,7 @@ Vector<3> Disturbances::GetAccelerationI() { return sum_acceleration_i_; } void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); - ini_fname_ = iniAccess.ReadString("DISTURBANCE", "dist_file"); + ini_fname_ = iniAccess.ReadString("DISTURBANCE", "disturbance_file"); GravityGradient* gg_dist = new GravityGradient(InitGravityGradient(ini_fname_, glo_env->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); disturbances_.push_back(gg_dist); diff --git a/src/Dynamics/Attitude/InitAttitude.cpp b/src/Dynamics/Attitude/InitAttitude.cpp index a203a7c29..e0a00ae28 100644 --- a/src/Dynamics/Attitude/InitAttitude.cpp +++ b/src/Dynamics/Attitude/InitAttitude.cpp @@ -10,7 +10,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel const Matrix<3, 3> inertia_tensor, const int sat_id) { IniAccess ini_file(file_name); const char* section_ = "ATTITUDE"; - std::string mc_name = section_ + std::to_string(sat_id); // "Attitude" + to_string(id); + std::string mc_name = section_ + std::to_string(sat_id); // FIXME Attitude* attitude; const std::string propagate_mode = ini_file.ReadString(section_, "propagate_mode"); @@ -18,11 +18,11 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel if (propagate_mode == "RK4") { // RK4 propagator Vector<3> omega_b; - ini_file.ReadVector(section_, "Omega_b", omega_b); + ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); Quaternion quaternion_i2b; - ini_file.ReadQuaternion(section_, "Quaternion_i2b", quaternion_i2b); + ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); Vector<3> torque_b; - ini_file.ReadVector(section_, "Torque_b", torque_b); + ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); attitude = new AttitudeRK4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); } else if (propagate_mode == "CONTROLLED") { @@ -35,10 +35,10 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel AttCtrlMode main_mode = ConvertStringToCtrlMode(main_mode_in); AttCtrlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); Quaternion quaternion_i2b; - ini_file_ca.ReadQuaternion(section_, "Quaternion_i2b", quaternion_i2b); + ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); Vector<3> pointing_t_b, pointing_sub_t_b; - ini_file_ca.ReadVector(section_ca_, "pointing_t_b", pointing_t_b); - ini_file_ca.ReadVector(section_ca_, "pointing_sub_t_b", pointing_sub_t_b); + ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", pointing_t_b); + ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", pointing_sub_t_b); attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, pointing_t_b, pointing_sub_t_b, inertia_tensor, celes_info, orbit, mc_name); } else { @@ -46,11 +46,11 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel std::cerr << "The attitude mode is automatically set as RK4" << std::endl; Vector<3> omega_b; - ini_file.ReadVector(section_, "Omega_b", omega_b); + ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); Quaternion quaternion_i2b; - ini_file.ReadQuaternion(section_, "Quaternion_i2b", quaternion_i2b); + ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); Vector<3> torque_b; - ini_file.ReadVector(section_, "Torque_b", torque_b); + ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); attitude = new AttitudeRK4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); } diff --git a/src/Dynamics/Orbit/InitOrbit.cpp b/src/Dynamics/Orbit/InitOrbit.cpp index 5fc30287d..1185b294e 100644 --- a/src/Dynamics/Orbit/InitOrbit.cpp +++ b/src/Dynamics/Orbit/InitOrbit.cpp @@ -50,42 +50,37 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d STMModel stm_model_type = (STMModel)(conf.ReadInt(section_, "stm_model_type")); Vector<3> init_relative_position_lvlh; - conf.ReadVector<3>(section_, "init_relative_position_lvlh", init_relative_position_lvlh); + conf.ReadVector<3>(section_, "initial_relative_position_lvlh_m", init_relative_position_lvlh); Vector<3> init_relative_velocity_lvlh; - conf.ReadVector<3>(section_, "init_relative_velocity_lvlh", init_relative_velocity_lvlh); + conf.ReadVector<3>(section_, "initial_relative_velocity_lvlh_m_s", init_relative_velocity_lvlh); // There is a possibility that the orbit of the reference sat is not initialized when RelativeOrbit initialization is called To ensure that // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat - int reference_sat_id = conf.ReadInt(section_, "reference_sat_id"); + int reference_sat_id = conf.ReadInt(section_, "reference_satellite_id"); orbit = new RelativeOrbit(celes_info, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, rel_info); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation - std::string init_mode_kepler = conf.ReadString(section_, "init_mode_kepler"); double mu_m3_s2 = gravity_constant; OrbitalElements oe; // TODO: init_mode_kepler should be removed in the next major update - if ((init_mode_kepler == "INIT_POSVEL" && initialize_mode == OrbitInitializeMode::kDefault) || - initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { + if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { // initialize with position and velocity Vector<3> init_pos_m; - conf.ReadVector<3>(section_, "init_position", init_pos_m); + conf.ReadVector<3>(section_, "initial_position_i_m", init_pos_m); Vector<3> init_vel_m_s; - conf.ReadVector<3>(section_, "init_velocity", init_vel_m_s); + conf.ReadVector<3>(section_, "initial_velocity_i_m_s", init_vel_m_s); oe = OrbitalElements(mu_m3_s2, current_jd, init_pos_m, init_vel_m_s); - } else if ((init_mode_kepler == "INIT_OE" && initialize_mode == OrbitInitializeMode::kDefault) || - initialize_mode == OrbitInitializeMode::kOrbitalElements) { + } else { // initialize with orbital elements double semi_major_axis_m = conf.ReadDouble(section_, "semi_major_axis_m"); double eccentricity = conf.ReadDouble(section_, "eccentricity"); double inclination_rad = conf.ReadDouble(section_, "inclination_rad"); double raan_rad = conf.ReadDouble(section_, "raan_rad"); - double arg_perigee_rad = conf.ReadDouble(section_, "arg_perigee_rad"); + double arg_perigee_rad = conf.ReadDouble(section_, "argument_of_perigee_rad"); double epoch_jday = conf.ReadDouble(section_, "epoch_jday"); oe = OrbitalElements(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); - } else { - std::cerr << "ERROR: Kepler orbit initialize mode: " << init_mode_kepler << " is not defined!" << std::endl; } KeplerOrbit kepler_orbit(mu_m3_s2, oe); orbit = new KeplerOrbitPropagation(celes_info, current_jd, kepler_orbit); @@ -133,7 +128,7 @@ Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3 double eccentricity = conf.ReadDouble(section_, "eccentricity"); double inclination_rad = conf.ReadDouble(section_, "inclination_rad"); double raan_rad = conf.ReadDouble(section_, "raan_rad"); - double arg_perigee_rad = conf.ReadDouble(section_, "arg_perigee_rad"); + double arg_perigee_rad = conf.ReadDouble(section_, "argument_of_perigee_rad"); double epoch_jday = conf.ReadDouble(section_, "epoch_jday"); OrbitalElements oe(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); KeplerOrbit kepler_orbit(mu_m3_s2, oe); @@ -142,14 +137,14 @@ Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3 position_i_m = kepler_orbit.GetPosition_i_m(); velocity_i_m_s = kepler_orbit.GetVelocity_i_m_s(); } else if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { - conf.ReadVector<3>(section_, "init_position", position_i_m); - conf.ReadVector<3>(section_, "init_velocity", velocity_i_m_s); + conf.ReadVector<3>(section_, "initial_position_i_m", position_i_m); + conf.ReadVector<3>(section_, "initial_velocity_i_m_s", velocity_i_m_s); } else { std::cerr << "WARNINGS: orbit initialize mode is not defined!" << std::endl; std::cerr << "The orbit is automatically initialized as default mode" << std::endl; - conf.ReadVector<3>(section_, "init_position", position_i_m); - conf.ReadVector<3>(section_, "init_velocity", velocity_i_m_s); + conf.ReadVector<3>(section_, "initial_position_i_m", position_i_m); + conf.ReadVector<3>(section_, "initial_velocity_i_m_s", velocity_i_m_s); } for (size_t i = 0; i < 3; i++) { diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index 30303846a..a11666a0a 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -53,7 +53,7 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st vector> vnodestr; // string vector of node property data int nodes_num = 1; - bool is_calc_enabled = mainIni.ReadBoolean("Thermal", "IsCalcEnabled"); + bool is_calc_enabled = mainIni.ReadEnable("Thermal", "calculation"); if (is_calc_enabled == false) { // Return here to avoid CSV file reading Temperature* temperature; @@ -62,7 +62,7 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st } // read ini-file settings - string file_path = mainIni.ReadString("Thermal", "thrm_file"); + string file_path = mainIni.ReadString("Thermal", "thermal_file_directory"); bool debug = mainIni.ReadBoolean("Thermal", "debug"); // Read Node Properties from CSV File diff --git a/src/Environment/Local/LocalEnvironment.cpp b/src/Environment/Local/LocalEnvironment.cpp index 9be225242..3a3edfff8 100644 --- a/src/Environment/Local/LocalEnvironment.cpp +++ b/src/Environment/Local/LocalEnvironment.cpp @@ -24,7 +24,7 @@ LocalEnvironment::~LocalEnvironment() { void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { // Read file name IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); - std::string ini_fname = iniAccess.ReadString("LOCAL_ENVIRONMENT", "local_env_file"); + std::string ini_fname = iniAccess.ReadString("LOCAL_ENVIRONMENT", "local_environment_file"); // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize From 097755c2709871cc1780fb77a0b6e3427c40f161 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Feb 2023 16:54:13 +0100 Subject: [PATCH 0055/1086] Fix ini file for ground station --- data/SampleSat/ini/SampleGS.ini | 4 ++-- .../GroundStation/SampleGroundStation/SampleGSComponents.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/SampleSat/ini/SampleGS.ini b/data/SampleSat/ini/SampleGS.ini index 68315a67c..9250ca030 100644 --- a/data/SampleSat/ini/SampleGS.ini +++ b/data/SampleSat/ini/SampleGS.ini @@ -8,5 +8,5 @@ height_m = 3.4 elevation_limit_angle_deg = 5.0 [COMPONENTS_FILE] -ant_gs_file = ../../data/SampleSat/ini/component/ANT_GS.ini -gs_calculator_file = ../../data/SampleSat/ini/component/GScalculator.ini +ground_station_antenna_file = ../../data/SampleSat/ini/component/ANT_GS.ini +ground_station_calculator_file = ../../data/SampleSat/ini/component/GScalculator.ini diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp b/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp index 5c681e83a..832738d25 100644 --- a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp +++ b/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp @@ -9,10 +9,10 @@ SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); - std::string ant_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ant_gs_file"); + std::string ant_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ground_station_antenna_file"); config_->main_logger_->CopyFileToLogDir(ant_ini_path); antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); - std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "gs_calculator_file"); + std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ground_station_calculator_file"); config_->main_logger_->CopyFileToLogDir(gscalculator_ini_path); gs_calculator_ = new GScalculator(InitGScalculator(gscalculator_ini_path)); } From 956e283dd1a7b66bc7fb5b5d9c7d7c1c96d2952f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:02:03 +0100 Subject: [PATCH 0056/1086] Rename initialize files --- .../initialize_files/sample_disturbance.ini} | 0 .../initialize_files/sample_gnss.ini} | 0 .../initialize_files/sample_ground_station.ini} | 0 .../sample_inter_satellite_communication.ini} | 0 .../initialize_files/sample_local_environment.ini} | 0 .../initialize_files/sample_satellite.ini} | 8 ++++---- .../initialize_files/sample_simulation_base.ini} | 8 ++++---- .../initialize_files/sample_structure.ini} | 0 .../initialize_files/sample_thermal.ini} | 0 src/S2E.cpp | 2 +- 10 files changed, 9 insertions(+), 9 deletions(-) rename data/{SampleSat/ini/SampleDisturbance.ini => sample/initialize_files/sample_disturbance.ini} (100%) rename data/{SampleSat/ini/SampleGNSS.ini => sample/initialize_files/sample_gnss.ini} (100%) rename data/{SampleSat/ini/SampleGS.ini => sample/initialize_files/sample_ground_station.ini} (100%) rename data/{SampleSat/ini/SampleInterSatComm.ini => sample/initialize_files/sample_inter_satellite_communication.ini} (100%) rename data/{SampleSat/ini/SampleLocalEnvironment.ini => sample/initialize_files/sample_local_environment.ini} (100%) rename data/{SampleSat/ini/SampleSat.ini => sample/initialize_files/sample_satellite.ini} (94%) rename data/{SampleSat/ini/SampleSimBase.ini => sample/initialize_files/sample_simulation_base.ini} (93%) rename data/{SampleSat/ini/SampleStructure.ini => sample/initialize_files/sample_structure.ini} (100%) rename data/{SampleSat/ini/SampleThermal.ini => sample/initialize_files/sample_thermal.ini} (100%) diff --git a/data/SampleSat/ini/SampleDisturbance.ini b/data/sample/initialize_files/sample_disturbance.ini similarity index 100% rename from data/SampleSat/ini/SampleDisturbance.ini rename to data/sample/initialize_files/sample_disturbance.ini diff --git a/data/SampleSat/ini/SampleGNSS.ini b/data/sample/initialize_files/sample_gnss.ini similarity index 100% rename from data/SampleSat/ini/SampleGNSS.ini rename to data/sample/initialize_files/sample_gnss.ini diff --git a/data/SampleSat/ini/SampleGS.ini b/data/sample/initialize_files/sample_ground_station.ini similarity index 100% rename from data/SampleSat/ini/SampleGS.ini rename to data/sample/initialize_files/sample_ground_station.ini diff --git a/data/SampleSat/ini/SampleInterSatComm.ini b/data/sample/initialize_files/sample_inter_satellite_communication.ini similarity index 100% rename from data/SampleSat/ini/SampleInterSatComm.ini rename to data/sample/initialize_files/sample_inter_satellite_communication.ini diff --git a/data/SampleSat/ini/SampleLocalEnvironment.ini b/data/sample/initialize_files/sample_local_environment.ini similarity index 100% rename from data/SampleSat/ini/SampleLocalEnvironment.ini rename to data/sample/initialize_files/sample_local_environment.ini diff --git a/data/SampleSat/ini/SampleSat.ini b/data/sample/initialize_files/sample_satellite.ini similarity index 94% rename from data/SampleSat/ini/SampleSat.ini rename to data/sample/initialize_files/sample_satellite.ini index 9a5d2efdb..4720c2bf9 100644 --- a/data/SampleSat/ini/SampleSat.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -120,18 +120,18 @@ error_tolerance = 0.0001 [Thermal] calculation = DISABLE debug = 0 -thermal_file_directory = ../../data/SampleSat/ini/Thermal_CSV/ +thermal_file_directory = ../../data/sample/initialize_files/Thermal_CSV/ [LOCAL_ENVIRONMENT] -local_environment_file = ../../data/SampleSat/ini/SampleLocalEnvironment.ini +local_environment_file = ../../data/sample/initialize_files/sample_local_environment.ini [DISTURBANCE] -disturbance_file = ../../data/SampleSat/ini/SampleDisturbance.ini +disturbance_file = ../../data/sample/initialize_files/sample_disturbance.ini [STRUCTURE_FILE] -structure_file = ../../data/SampleSat/ini/SampleStructure.ini +structure_file = ../../data/sample/initialize_files/sample_structure.ini [COMPONENTS_FILE] diff --git a/data/SampleSat/ini/SampleSimBase.ini b/data/sample/initialize_files/sample_simulation_base.ini similarity index 93% rename from data/SampleSat/ini/SampleSimBase.ini rename to data/sample/initialize_files/sample_simulation_base.ini index 6659c89f0..6c88d3cde 100644 --- a/data/SampleSat/ini/SampleSimBase.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -132,7 +132,7 @@ save_initialize_files = ENABLE // File name must not over 256 characters (defined in initialize.h as MAX_CHAR_NUM) // If you want to add a spacecraft, create the corresponding Sat.ini, and specify it as sat_file(1), sat_file(2)... . number_of_simulated_spacecraft = 1 -spacecraft_file(0) = ../../data/SampleSat/ini/SampleSat.ini -ground_station_file = ../../data/SampleSat/ini/SampleGS.ini -gnss_file = ../../data/SampleSat/ini/SampleGNSS.ini -log_file_save_directory = ../../data/SampleSat/logs/ +spacecraft_file(0) = ../../data/sample/initialize_files/sample_satellite.ini +ground_station_file = ../../data/sample/initialize_files/sample_ground_station.ini +gnss_file = ../../data/sample/initialize_files/sample_gnss.ini +log_file_save_directory = ../../data/sample/logs/ diff --git a/data/SampleSat/ini/SampleStructure.ini b/data/sample/initialize_files/sample_structure.ini similarity index 100% rename from data/SampleSat/ini/SampleStructure.ini rename to data/sample/initialize_files/sample_structure.ini diff --git a/data/SampleSat/ini/SampleThermal.ini b/data/sample/initialize_files/sample_thermal.ini similarity index 100% rename from data/SampleSat/ini/SampleThermal.ini rename to data/sample/initialize_files/sample_thermal.ini diff --git a/src/S2E.cpp b/src/S2E.cpp index 62ce2a969..fc52a4b52 100644 --- a/src/S2E.cpp +++ b/src/S2E.cpp @@ -47,7 +47,7 @@ int main(int argc, char *argv[]) start = system_clock::now(); std::string data_path = "../../data/"; - std::string ini_file = "../../data/SampleSat/ini/SampleSimBase.ini"; + std::string ini_file = "../../data/sample/initialize_files/sample_simulation_base.ini"; // Parsing arguments: SatAttSim [ini_file] if (argc == 0) { From f0144f869cb147ef41368c7f05551653fda32322 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:10:48 +0100 Subject: [PATCH 0057/1086] Rename thermal csv files --- data/sample/initialize_files/sample_satellite.ini | 2 +- .../initialize_files/thermal_csv_files/cij.csv} | 0 .../initialize_files/thermal_csv_files/heaters.csv} | 0 .../initialize_files/thermal_csv_files/node.csv} | 0 .../initialize_files/thermal_csv_files/rij.csv} | 0 .../thermal_csv_files/temperture_sensors.csv} | 0 .../thermal_csv_files/thermal_components.csv} | 0 src/Dynamics/Thermal/InitTemperature.cpp | 10 +++++----- 8 files changed, 6 insertions(+), 6 deletions(-) rename data/{SampleSat/ini/Thermal_CSV/Cij.csv => sample/initialize_files/thermal_csv_files/cij.csv} (100%) rename data/{SampleSat/ini/Thermal_CSV/Heaters.csv => sample/initialize_files/thermal_csv_files/heaters.csv} (100%) rename data/{SampleSat/ini/Thermal_CSV/Node.csv => sample/initialize_files/thermal_csv_files/node.csv} (100%) rename data/{SampleSat/ini/Thermal_CSV/Rij.csv => sample/initialize_files/thermal_csv_files/rij.csv} (100%) rename data/{SampleSat/ini/Thermal_CSV/TempSensors.csv => sample/initialize_files/thermal_csv_files/temperture_sensors.csv} (100%) rename data/{SampleSat/ini/Thermal_CSV/ThermoCompo.csv => sample/initialize_files/thermal_csv_files/thermal_components.csv} (100%) diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index 4720c2bf9..f42b0b3b7 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -120,7 +120,7 @@ error_tolerance = 0.0001 [Thermal] calculation = DISABLE debug = 0 -thermal_file_directory = ../../data/sample/initialize_files/Thermal_CSV/ +thermal_file_directory = ../../data/sample/initialize_files/thermal_csv_files/ [LOCAL_ENVIRONMENT] local_environment_file = ../../data/sample/initialize_files/sample_local_environment.ini diff --git a/data/SampleSat/ini/Thermal_CSV/Cij.csv b/data/sample/initialize_files/thermal_csv_files/cij.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/Cij.csv rename to data/sample/initialize_files/thermal_csv_files/cij.csv diff --git a/data/SampleSat/ini/Thermal_CSV/Heaters.csv b/data/sample/initialize_files/thermal_csv_files/heaters.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/Heaters.csv rename to data/sample/initialize_files/thermal_csv_files/heaters.csv diff --git a/data/SampleSat/ini/Thermal_CSV/Node.csv b/data/sample/initialize_files/thermal_csv_files/node.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/Node.csv rename to data/sample/initialize_files/thermal_csv_files/node.csv diff --git a/data/SampleSat/ini/Thermal_CSV/Rij.csv b/data/sample/initialize_files/thermal_csv_files/rij.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/Rij.csv rename to data/sample/initialize_files/thermal_csv_files/rij.csv diff --git a/data/SampleSat/ini/Thermal_CSV/TempSensors.csv b/data/sample/initialize_files/thermal_csv_files/temperture_sensors.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/TempSensors.csv rename to data/sample/initialize_files/thermal_csv_files/temperture_sensors.csv diff --git a/data/SampleSat/ini/Thermal_CSV/ThermoCompo.csv b/data/sample/initialize_files/thermal_csv_files/thermal_components.csv similarity index 100% rename from data/SampleSat/ini/Thermal_CSV/ThermoCompo.csv rename to data/sample/initialize_files/thermal_csv_files/thermal_components.csv diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index a11666a0a..f6cf45257 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -7,8 +7,8 @@ #include "InitNode.hpp" -/* Import node properties and Cij/Rij Datas by reading CSV File (Node.csv, -Cij.csv, Rij.csv) Detailed process of reading node properties from CSV File, and +/* Import node properties and Cij/Rij Datas by reading CSV File (node.csv, +cij.csv, rij.csv) Detailed process of reading node properties from CSV File, and CSV file formats of node properties is written in Init_Node.cpp [File Formats of Node.csv] @@ -66,7 +66,7 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st bool debug = mainIni.ReadBoolean("Thermal", "debug"); // Read Node Properties from CSV File - string filepath_node = file_path + "Node.csv"; + string filepath_node = file_path + "node.csv"; IniAccess conf_node(filepath_node); conf_node.ReadCsvString(vnodestr, 100); /*since we don't know the number of nodes yet, set nodes_num=100 temporary. @@ -79,8 +79,8 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st } // Read Cij,Rij data from CSV File - string filepath_cij = file_path + "Cij.csv"; - string filepath_rij = file_path + "Rij.csv"; + string filepath_cij = file_path + "cij.csv"; + string filepath_rij = file_path + "rij.csv"; IniAccess conf_cij(filepath_cij); IniAccess conf_rij(filepath_rij); conf_cij.ReadCsvDouble(cij, From be3271f70d35cef6cacc9dc02bcd865e53a57d12 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:24:39 +0100 Subject: [PATCH 0058/1086] Rename component initialize files --- .../initialize_files/components/battery.ini} | 0 .../components/force_generator.ini} | 0 .../components/gnss_receiver.ini} | 0 .../components/ground_station_antenna.ini} | 0 .../components/ground_station_calculator.ini} | 0 .../components/gyro_sensor.ini} | 0 .../components/magnetometer.ini} | 0 .../components/magnetorquer.ini} | 0 .../components/reaction_wheel.ini} | 0 .../components/solar_array_panel.ini} | 0 .../components/spacecraft_antenna.ini} | 0 .../components/star_sensor.ini} | 0 .../components/sun_sensor.ini} | 0 .../components/telescope.ini} | 0 .../initialize_files/components/thruster.ini} | 0 .../sample_ground_station.ini | 4 ++-- .../initialize_files/sample_satellite.ini | 20 +++++++++---------- 17 files changed, 12 insertions(+), 12 deletions(-) rename data/{SampleSat/ini/component/BAT.ini => sample/initialize_files/components/battery.ini} (100%) rename data/{SampleSat/ini/component/ForceGenerator.ini => sample/initialize_files/components/force_generator.ini} (100%) rename data/{SampleSat/ini/component/GNSSReceiver.ini => sample/initialize_files/components/gnss_receiver.ini} (100%) rename data/{SampleSat/ini/component/ANT_GS.ini => sample/initialize_files/components/ground_station_antenna.ini} (100%) rename data/{SampleSat/ini/component/GScalculator.ini => sample/initialize_files/components/ground_station_calculator.ini} (100%) rename data/{SampleSat/ini/component/gyro.ini => sample/initialize_files/components/gyro_sensor.ini} (100%) rename data/{SampleSat/ini/component/magsensor.ini => sample/initialize_files/components/magnetometer.ini} (100%) rename data/{SampleSat/ini/component/magtorquer.ini => sample/initialize_files/components/magnetorquer.ini} (100%) rename data/{SampleSat/ini/component/RW.ini => sample/initialize_files/components/reaction_wheel.ini} (100%) rename data/{SampleSat/ini/component/SAP.ini => sample/initialize_files/components/solar_array_panel.ini} (100%) rename data/{SampleSat/ini/component/ANT_SC.ini => sample/initialize_files/components/spacecraft_antenna.ini} (100%) rename data/{SampleSat/ini/component/STT.ini => sample/initialize_files/components/star_sensor.ini} (100%) rename data/{SampleSat/ini/component/SS.ini => sample/initialize_files/components/sun_sensor.ini} (100%) rename data/{SampleSat/ini/component/Telescope.ini => sample/initialize_files/components/telescope.ini} (100%) rename data/{SampleSat/ini/component/Thruster.ini => sample/initialize_files/components/thruster.ini} (100%) diff --git a/data/SampleSat/ini/component/BAT.ini b/data/sample/initialize_files/components/battery.ini similarity index 100% rename from data/SampleSat/ini/component/BAT.ini rename to data/sample/initialize_files/components/battery.ini diff --git a/data/SampleSat/ini/component/ForceGenerator.ini b/data/sample/initialize_files/components/force_generator.ini similarity index 100% rename from data/SampleSat/ini/component/ForceGenerator.ini rename to data/sample/initialize_files/components/force_generator.ini diff --git a/data/SampleSat/ini/component/GNSSReceiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini similarity index 100% rename from data/SampleSat/ini/component/GNSSReceiver.ini rename to data/sample/initialize_files/components/gnss_receiver.ini diff --git a/data/SampleSat/ini/component/ANT_GS.ini b/data/sample/initialize_files/components/ground_station_antenna.ini similarity index 100% rename from data/SampleSat/ini/component/ANT_GS.ini rename to data/sample/initialize_files/components/ground_station_antenna.ini diff --git a/data/SampleSat/ini/component/GScalculator.ini b/data/sample/initialize_files/components/ground_station_calculator.ini similarity index 100% rename from data/SampleSat/ini/component/GScalculator.ini rename to data/sample/initialize_files/components/ground_station_calculator.ini diff --git a/data/SampleSat/ini/component/gyro.ini b/data/sample/initialize_files/components/gyro_sensor.ini similarity index 100% rename from data/SampleSat/ini/component/gyro.ini rename to data/sample/initialize_files/components/gyro_sensor.ini diff --git a/data/SampleSat/ini/component/magsensor.ini b/data/sample/initialize_files/components/magnetometer.ini similarity index 100% rename from data/SampleSat/ini/component/magsensor.ini rename to data/sample/initialize_files/components/magnetometer.ini diff --git a/data/SampleSat/ini/component/magtorquer.ini b/data/sample/initialize_files/components/magnetorquer.ini similarity index 100% rename from data/SampleSat/ini/component/magtorquer.ini rename to data/sample/initialize_files/components/magnetorquer.ini diff --git a/data/SampleSat/ini/component/RW.ini b/data/sample/initialize_files/components/reaction_wheel.ini similarity index 100% rename from data/SampleSat/ini/component/RW.ini rename to data/sample/initialize_files/components/reaction_wheel.ini diff --git a/data/SampleSat/ini/component/SAP.ini b/data/sample/initialize_files/components/solar_array_panel.ini similarity index 100% rename from data/SampleSat/ini/component/SAP.ini rename to data/sample/initialize_files/components/solar_array_panel.ini diff --git a/data/SampleSat/ini/component/ANT_SC.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini similarity index 100% rename from data/SampleSat/ini/component/ANT_SC.ini rename to data/sample/initialize_files/components/spacecraft_antenna.ini diff --git a/data/SampleSat/ini/component/STT.ini b/data/sample/initialize_files/components/star_sensor.ini similarity index 100% rename from data/SampleSat/ini/component/STT.ini rename to data/sample/initialize_files/components/star_sensor.ini diff --git a/data/SampleSat/ini/component/SS.ini b/data/sample/initialize_files/components/sun_sensor.ini similarity index 100% rename from data/SampleSat/ini/component/SS.ini rename to data/sample/initialize_files/components/sun_sensor.ini diff --git a/data/SampleSat/ini/component/Telescope.ini b/data/sample/initialize_files/components/telescope.ini similarity index 100% rename from data/SampleSat/ini/component/Telescope.ini rename to data/sample/initialize_files/components/telescope.ini diff --git a/data/SampleSat/ini/component/Thruster.ini b/data/sample/initialize_files/components/thruster.ini similarity index 100% rename from data/SampleSat/ini/component/Thruster.ini rename to data/sample/initialize_files/components/thruster.ini diff --git a/data/sample/initialize_files/sample_ground_station.ini b/data/sample/initialize_files/sample_ground_station.ini index 9250ca030..1fd645b73 100644 --- a/data/sample/initialize_files/sample_ground_station.ini +++ b/data/sample/initialize_files/sample_ground_station.ini @@ -8,5 +8,5 @@ height_m = 3.4 elevation_limit_angle_deg = 5.0 [COMPONENTS_FILE] -ground_station_antenna_file = ../../data/SampleSat/ini/component/ANT_GS.ini -ground_station_calculator_file = ../../data/SampleSat/ini/component/GScalculator.ini +ground_station_antenna_file = ../../data/sample/initialize_files/components/ground_station_antenna.ini +ground_station_calculator_file = ../../data/sample/initialize_files/components/ground_station_calculator.ini diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index f42b0b3b7..6418033e0 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -135,13 +135,13 @@ structure_file = ../../data/sample/initialize_files/sample_structure.ini [COMPONENTS_FILE] -gyro_file = ../../data/SampleSat/ini/component/gyro.ini -magetometer_file = ../../data/SampleSat/ini/component/magsensor.ini -stt_file = ../../data/SampleSat/ini/component/STT.ini -ss_file = ../../data/SampleSat/ini/component/SS.ini -gnss_file = ../../data/SampleSat/ini/component/GNSSReceiver.ini -magetorquer_file = ../../data/SampleSat/ini/component/magtorquer.ini -rw_file = ../../data/SampleSat/ini/component/RW.ini -thruster_file = ../../data/SampleSat/ini/component/Thruster.ini -force_generator_file = ../../data/SampleSat/ini/component/ForceGenerator.ini -antenna_file = ../../data/SampleSat/ini/component/ANT_SC.ini +gyro_file = ../../data/sample/initialize_files/components/gyro_sensor.ini +magetometer_file = ../../data/sample/initialize_files/components/magnetometer.ini +stt_file = ../../data/sample/initialize_files/components/star_sensor.ini +ss_file = ../../data/sample/initialize_files/components/sun_sensor.ini +gnss_file = ../../data/sample/initialize_files/components/gnss_receiver.ini +magetorquer_file = ../../data/sample/initialize_files/components/magnetorquer.ini +rw_file = ../../data/sample/initialize_files/components/reaction_wheel.ini +thruster_file = ../../data/sample/initialize_files/components/thruster.ini +force_generator_file = ../../data/sample/initialize_files/components/force_generator.ini +antenna_file = ../../data/sample/initialize_files/components/spacecraft_antenna.ini From bf844cce8aa27a8c005f005d845294cf2ece4d9f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:35:37 +0100 Subject: [PATCH 0059/1086] Rename initialize file of torque generator --- .../initialize_files/components/torque_generator.ini} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename data/{SampleSat/ini/component/TorqueGenerator.ini => sample/initialize_files/components/torque_generator.ini} (100%) diff --git a/data/SampleSat/ini/component/TorqueGenerator.ini b/data/sample/initialize_files/components/torque_generator.ini similarity index 100% rename from data/SampleSat/ini/component/TorqueGenerator.ini rename to data/sample/initialize_files/components/torque_generator.ini From 04e67ea34957aacfb67fa8fcb1c3fd30ce753ddb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:37:31 +0100 Subject: [PATCH 0060/1086] Delete unused initialize files --- data/SampleSat/ini/component/ANT.ini | 146 -------------------------- data/SampleSat/ini/component/SADA.ini | 37 ------- 2 files changed, 183 deletions(-) delete mode 100644 data/SampleSat/ini/component/ANT.ini delete mode 100644 data/SampleSat/ini/component/SADA.ini diff --git a/data/SampleSat/ini/component/ANT.ini b/data/SampleSat/ini/component/ANT.ini deleted file mode 100644 index fb3d07652..000000000 --- a/data/SampleSat/ini/component/ANT.ini +++ /dev/null @@ -1,146 +0,0 @@ -[ANT1] -// Example of antenna on spacecraft - -// Quaternion converts body-fixed frame to component frame -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 - -// Flag for transmitter or not -is_transmitter = 1 - -// Flag for receiver or not -is_receiver = 1 - -// frequency [MHz] -frequency = 8200.0 - -// Parameters for transmitter -// RF output power [W] -tx_output = 1.0 - -// Feeder loss [dB] -tx_loss_feeder = -1.5 - -// Pointing loss [dB] -tx_loss_pointing = 0.0 - -// Antenna gain model -// ISOTROPIC: Ideal isotropic antenna -// RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = RADIATION_PATTERN_CSV - -// Gain for ISOTROPIC mode [dBi] -// Generally, it is zero but users can set any value for ideal analysis -tx_gain = 8.0 - -// Antenna radiation pattern CSV file path -tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv -// General information of the CSV file -tx_length_theta = 360 -tx_length_phi = 181 -tx_theta_max_rad = 6.28 -tx_phi_max_rad = 3.14 - - -// Parameters for receiver -// Feeder loss [dB] -rx_loss_feeder = -0.5 - -// Pointing loss [dB] -rx_loss_pointing = -0.5 - -// System noise temperature [K] -rx_system_noise_temperature = 230 - -// Antenna gain model -// ISOTROPIC: Ideal isotropic antenna -// RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = RADIATION_PATTERN_CSV - -// Gain for ISOTROPIC mode [dBi] -// Generally, it is zero but users can set any value for ideal analysis -rx_gain = 43.27 - -// Antenna radiation pattern CSV file path -rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv -// General information of the CSV file -rx_length_theta = 360 -rx_length_phi = 181 -rx_theta_max_rad = 6.28 -rx_phi_max_rad = 3.14 - - -[ANT2] -// Example of antenna on ground station - -// Quaternion converts body-fixed frame to component frame -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 - -// Flag for transmitter or not -is_transmitter = 0 - -// Flag for receiver or not -is_receiver = 1 - -// frequency [MHz] -frequency = 8200.0 - -// Parameters for transmitter -// RF output power [W] -tx_output = 1.0 - -// Feeder loss [dB] -tx_loss_feeder = -1.5 - -// Pointing loss [dB] -tx_loss_pointing = 0.0 - -// Antenna gain model -// ISOTROPIC: Ideal isotropic antenna -// RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = RADIATION_PATTERN_CSV - -// Gain for ISOTROPIC mode [dBi] -// Generally, it is zero but users can set any value for ideal analysis -tx_gain = 12.0 - -// Antenna radiation pattern CSV file path -tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv -// General information of the CSV file -tx_length_theta = 360 -tx_length_phi = 181 -tx_theta_max_rad = 6.28 -tx_phi_max_rad = 3.14 - - -// Parameters for receiver -// Feeder loss [dB] -rx_loss_feeder = -0.5 - -// Pointing loss [dB] -rx_loss_pointing = -0.5 - -// System noise temperature [K] -rx_system_noise_temperature = 230 - -// Antenna gain model -// ISOTROPIC: Ideal isotropic antenna -// RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = RADIATION_PATTERN_CSV - -// Gain for ISOTROPIC mode [dBi] -// Generally, it is zero but users can set any value for ideal analysis -rx_gain = 43.27 - -// Antenna radiation pattern CSV file path -rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv -// General information of the CSV file -rx_length_theta = 360 -rx_length_phi = 181 -rx_theta_max_rad = 6.28 -rx_phi_max_rad = 3.14 diff --git a/data/SampleSat/ini/component/SADA.ini b/data/SampleSat/ini/component/SADA.ini deleted file mode 100644 index 98394a730..000000000 --- a/data/SampleSat/ini/component/SADA.ini +++ /dev/null @@ -1,37 +0,0 @@ -[SADA1] -//コンポ製品名 - -//OBCと通信するポート -port_id = 5 - -//SADA通信頻度[Hz] -com_frequency = 20 - -//発電効率 -efficiency = 0.8 - -//SAP面積[m2] -sap_area = 0.04392387 - -//回転角が0度の時のSAP法線ベクトル -normal_vector_origin(0) = 0 -normal_vector_origin(1) = 0 -normal_vector_origin(2) = 1 - -//SAP回転軸 -axis_rot(0) = 1 -axis_rot(1) = 0 -axis_rot(2) = 0 - -//定常バイアス(回転角目標値と,回転後の回転角の差[deg]) -angle_control_bias_deg = 1 - -//バイアスランダム成分標準偏差 -angle_control_sigma = 0 - -//角度計測誤差標準偏差 -angle_measure_sigma = 0 - -//発電量計測誤差標準偏差 -power_measure_sigma = 0 - From c9ba64ac6d9c09b48a427b1277d29670013a3a43 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:42:18 +0100 Subject: [PATCH 0061/1086] Rename component csv files --- .../sample_antenna_radiation_pattern.csv} | 0 .../initialize_files/components/pcu_initial_study.ini} | 0 .../radial_force_harmonics_coefficients.csv} | 0 .../radial_torque_harmonics_coefficients.csv} | 0 .../initialize_files/components/thermal_components.ini} | 0 5 files changed, 0 insertions(+), 0 deletions(-) rename data/{SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv => sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv} (100%) rename data/{SampleSat/ini/component/PCU_InitialStudy.ini => sample/initialize_files/components/pcu_initial_study.ini} (100%) rename data/{SampleSat/ini/component/RWDisturbance/radial_force_harmonics_coef.csv => sample/initialize_files/components/rw_disturbance_csv_files/radial_force_harmonics_coefficients.csv} (100%) rename data/{SampleSat/ini/component/RWDisturbance/radial_torque_harmonics_coef.csv => sample/initialize_files/components/rw_disturbance_csv_files/radial_torque_harmonics_coefficients.csv} (100%) rename data/{SampleSat/ini/component/ThermoCompo.ini => sample/initialize_files/components/thermal_components.ini} (100%) diff --git a/data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv b/data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv similarity index 100% rename from data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv rename to data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv diff --git a/data/SampleSat/ini/component/PCU_InitialStudy.ini b/data/sample/initialize_files/components/pcu_initial_study.ini similarity index 100% rename from data/SampleSat/ini/component/PCU_InitialStudy.ini rename to data/sample/initialize_files/components/pcu_initial_study.ini diff --git a/data/SampleSat/ini/component/RWDisturbance/radial_force_harmonics_coef.csv b/data/sample/initialize_files/components/rw_disturbance_csv_files/radial_force_harmonics_coefficients.csv similarity index 100% rename from data/SampleSat/ini/component/RWDisturbance/radial_force_harmonics_coef.csv rename to data/sample/initialize_files/components/rw_disturbance_csv_files/radial_force_harmonics_coefficients.csv diff --git a/data/SampleSat/ini/component/RWDisturbance/radial_torque_harmonics_coef.csv b/data/sample/initialize_files/components/rw_disturbance_csv_files/radial_torque_harmonics_coefficients.csv similarity index 100% rename from data/SampleSat/ini/component/RWDisturbance/radial_torque_harmonics_coef.csv rename to data/sample/initialize_files/components/rw_disturbance_csv_files/radial_torque_harmonics_coefficients.csv diff --git a/data/SampleSat/ini/component/ThermoCompo.ini b/data/sample/initialize_files/components/thermal_components.ini similarity index 100% rename from data/SampleSat/ini/component/ThermoCompo.ini rename to data/sample/initialize_files/components/thermal_components.ini From 43b8319bf6b520be84938cd0cfe552d4d11d2ee1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:43:49 +0100 Subject: [PATCH 0062/1086] Fix thermal csv directory path --- data/sample/initialize_files/components/thermal_components.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/thermal_components.ini b/data/sample/initialize_files/components/thermal_components.ini index b562e71de..df1776fb3 100644 --- a/data/sample/initialize_files/components/thermal_components.ini +++ b/data/sample/initialize_files/components/thermal_components.ini @@ -1,4 +1,4 @@ [ThermoCompo1] is_debug = 0 is_zeus_correct_enabled = 1 -file_path = data/ini/Thermal_CSV/ \ No newline at end of file +file_path = data/ini/thermal_csv_files/ \ No newline at end of file From 3c391def7ea22b72330e5deb712d384e52d8ace2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 20:47:25 +0100 Subject: [PATCH 0063/1086] Fix log output for torque generator --- src/Component/IdealComponents/TorqueGenerator.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Component/IdealComponents/TorqueGenerator.cpp b/src/Component/IdealComponents/TorqueGenerator.cpp index c263fdedb..d7c987634 100644 --- a/src/Component/IdealComponents/TorqueGenerator.cpp +++ b/src/Component/IdealComponents/TorqueGenerator.cpp @@ -41,7 +41,7 @@ void TorqueGenerator::PowerOffRoutine() { generated_torque_b_Nm_ *= 0.0; } std::string TorqueGenerator::GetLogHeader() const { std::string str_tmp = ""; - std::string head = "IdealTorqueGenerator_"; + std::string head = "ideal_torque_generator_"; str_tmp += WriteVector(head + "ordered_torque", "b", "Nm", 3); str_tmp += WriteVector(head + "generated_torque", "b", "Nm", 3); From 736e3fd1107360804e9e3ea977781ea55b1111a7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 21:15:40 +0100 Subject: [PATCH 0064/1086] Fix small --- src/Environment/Global/SimTime.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Environment/Global/SimTime.cpp b/src/Environment/Global/SimTime.cpp index 3c631ce79..95ce8b10e 100644 --- a/src/Environment/Global/SimTime.cpp +++ b/src/Environment/Global/SimTime.cpp @@ -206,7 +206,7 @@ string SimTime::GetLogValue() const { const char kSize = 100; char ymdhms[kSize]; - snprintf(ymdhms, kSize, "%4d/%02d/%02d %02d:%02d:%.3lf", current_utc_.year, current_utc_.month, current_utc_.day, current_utc_.hour, + snprintf(ymdhms, kSize, "%4d/%02d/%02d %02d:%02d:%.3lf,", current_utc_.year, current_utc_.month, current_utc_.day, current_utc_.hour, current_utc_.min, current_utc_.sec); str_tmp += ymdhms; From 44cdbe995b45413bc68a2e2fc5a8a6a09568c36d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 21:20:38 +0100 Subject: [PATCH 0065/1086] Move log directory --- data/sample/logs/.gitkeep | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 data/sample/logs/.gitkeep diff --git a/data/sample/logs/.gitkeep b/data/sample/logs/.gitkeep new file mode 100644 index 000000000..e69de29bb From b6794016797857c5ebba478c19e4b9b98a68da8f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Feb 2023 21:29:52 +0100 Subject: [PATCH 0066/1086] Fix workflow --- .github/workflows/build.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 94764cebe..3ba2d4975 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -101,12 +101,12 @@ jobs: - name: fix simulation config shell: bash - working-directory: ./data/SampleSat/ini + working-directory: ./data/sample/initialize_files run: | find . -type f -name '*.ini' -exec sed -i 's/..\/..\/..\/ExtLibraries/..\/..\/ExtLibraries/g' {} \; - name: run simulation(SampleSat) - working-directory: ./data/SampleSat + working-directory: ./data/sample run: | ..\..\Debug\S2E.exe @@ -190,17 +190,17 @@ jobs: cmake --build . - name: fix simulation config - working-directory: ./data/SampleSat/ini + working-directory: ./data/sample/initialize_files run: | find . -type f -name '*.ini' -exec sed -i 's/..\/..\/..\/ExtLibraries/..\/..\/ExtLibraries/g' {} \; - name: run simulation(SampleSat) - working-directory: ./data/SampleSat + working-directory: ./data/sample run: | ../../S2E - name: generate graph - working-directory: ./data/SampleSat + working-directory: ./data/sample run: | sudo apt-get install -y gnuplot pip3 install yq From dd47266e339f44177ccc960180416f2d5c82064c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 10:43:55 +0100 Subject: [PATCH 0067/1086] Fix plot directory --- scripts/Plot/plot_gs_visibility.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 97dd90c50..2b74a2dd6 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -25,7 +25,7 @@ aparser = argparse.ArgumentParser() -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') +aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/sample/logs"', default='../../data/sample/logs') aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') aparser.add_argument('--no-gui', action='store_true') @@ -46,7 +46,7 @@ print("log: " + read_file_tag) # Read Gound Station position from the ini file in the logs directory -gs_ini_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + "/SampleGS.ini" +gs_ini_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + "/sample_ground_station.ini" configur = ConfigParser(comment_prefixes=('#', ';', '//'), inline_comment_prefixes=('#', ';', '//')) configur.read(gs_ini_file_name) gs_lat_deg = configur.getfloat('GS0', 'latitude_deg') From e8fecbcdf955521e18e3d7089f82b7f103f584eb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 10:54:48 +0100 Subject: [PATCH 0068/1086] Fix ini file for battery --- .../initialize_files/components/battery.ini | 30 +++++++++---------- src/Component/Power/InitBat.cpp | 10 +++---- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/data/sample/initialize_files/components/battery.ini b/data/sample/initialize_files/components/battery.ini index aea7da4c4..011bd173d 100644 --- a/data/sample/initialize_files/components/battery.ini +++ b/data/sample/initialize_files/components/battery.ini @@ -8,27 +8,27 @@ number_of_series = 3 number_of_parallel = 2 // Current capacity of a battery cell [Ah] -cell_capacity = 3.2 +cell_capacity_Ah = 3.2 // Polynomial approximation of the battery voltage -approx_order = 7 -cell_discharge_curve_coeffs(0) = 4.2 -cell_discharge_curve_coeffs(1)= -1.11372443 -cell_discharge_curve_coeffs(2)= 3.255553766 -cell_discharge_curve_coeffs(3)= -5.717011044 -cell_discharge_curve_coeffs(4)= 5.031000929 -cell_discharge_curve_coeffs(5)= -2.315028915 -cell_discharge_curve_coeffs(6)= 0.5338229034 -cell_discharge_curve_coeffs(7)= -0.04872142307 - -// Initial Discharge Of Depth of the battery module +approximation_order = 7 +cell_discharge_curve_coefficients(0) = 4.2 +cell_discharge_curve_coefficients(1)= -1.11372443 +cell_discharge_curve_coefficients(2)= 3.255553766 +cell_discharge_curve_coefficients(3)= -5.717011044 +cell_discharge_curve_coefficients(4)= 5.031000929 +cell_discharge_curve_coefficients(5)= -2.315028915 +cell_discharge_curve_coefficients(6)= 0.5338229034 +cell_discharge_curve_coefficients(7)= -0.04872142307 + +// Initial Discharge Of Depth (DoD) of the battery module initial_dod = 20.0 // Constant charge current [C] -cc_charge_c_rate = 0.2 +constant_charge_current_rate_C = 0.2 // Constant charge voltage [V] -cv_charge_voltage = 12.3 +constant_voltage_charge_voltage_V = 12.3 // Battery internal registance + wire/connector resistance between BAT and PCU [Ohm] -bat_resistance = 0.4 \ No newline at end of file +battery_resistance_Ohm = 0.4 \ No newline at end of file diff --git a/src/Component/Power/InitBat.cpp b/src/Component/Power/InitBat.cpp index 20a7dca82..b310acaf1 100644 --- a/src/Component/Power/InitBat.cpp +++ b/src/Component/Power/InitBat.cpp @@ -32,24 +32,24 @@ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, doub cell_capacity = bat_conf.ReadDouble(Section, "cell_capacity"); int approx_order; - approx_order = bat_conf.ReadInt(Section, "approx_order"); + approx_order = bat_conf.ReadInt(Section, "approximation_order"); std::vector cell_discharge_curve_coeffs; for (int i = 0; i <= approx_order; ++i) { - cell_discharge_curve_coeffs.push_back(bat_conf.ReadDouble(Section, ("cell_discharge_curve_coeffs(" + std::to_string(i) + ")").c_str())); + cell_discharge_curve_coeffs.push_back(bat_conf.ReadDouble(Section, ("cell_discharge_curve_coefficients(" + std::to_string(i) + ")").c_str())); } double initial_dod; initial_dod = bat_conf.ReadDouble(Section, "initial_dod"); double cc_charge_c_rate; - cc_charge_c_rate = bat_conf.ReadDouble(Section, "cc_charge_c_rate"); + cc_charge_c_rate = bat_conf.ReadDouble(Section, "constant_charge_current_rate_C"); double cv_charge_voltage; - cv_charge_voltage = bat_conf.ReadDouble(Section, "cv_charge_voltage"); + cv_charge_voltage = bat_conf.ReadDouble(Section, "constant_voltage_charge_voltage_V"); double bat_resistance; - bat_resistance = bat_conf.ReadDouble(Section, "bat_resistance"); + bat_resistance = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); BAT bat(prescaler, clock_gen, number_of_series, number_of_parallel, cell_capacity, cell_discharge_curve_coeffs, initial_dod, cc_charge_c_rate, cv_charge_voltage, bat_resistance, compo_step_time); From e2490c9991344e9c8195c9ede382cd5840865557 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:00:01 +0100 Subject: [PATCH 0069/1086] Fix ini file for SAP --- .../components/solar_array_panel.ini | 38 +++++++++---------- src/Component/Power/InitSap.cpp | 8 ++-- 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/data/sample/initialize_files/components/solar_array_panel.ini b/data/sample/initialize_files/components/solar_array_panel.ini index 30674d71a..eaccdebc6 100644 --- a/data/sample/initialize_files/components/solar_array_panel.ini +++ b/data/sample/initialize_files/components/solar_array_panel.ini @@ -1,13 +1,13 @@ [SAP1] prescaler = 10 -// Area of a solar cell [m^2] -cell_area = 0.0026 +// Area of a solar cell [m2] +cell_area_m2 = 0.0026 -// Normal vector -normal_vector(0) = 0.0 -normal_vector(1) = 1.0 -normal_vector(2) = 0.0 +// Normal vector at body fixed frame +normal_vector_b(0) = 0.0 +normal_vector_b(1) = 1.0 +normal_vector_b(2) = 0.0 // Power conversion efficiency cell_efficiency = 0.3 @@ -25,13 +25,13 @@ number_of_parallel = 6 [SAP2] prescaler = 10 -// Area of a solar cell [m^2] -cell_area = 0.0026 +// Area of a solar cell [m2] +cell_area_m2 = 0.0026 -// Normal vector -normal_vector(0) = 1.0 -normal_vector(1) = 0.0 -normal_vector(2) = 0.0 +// Normal vector at body fixed frame +normal_vector_b(0) = 1.0 +normal_vector_b(1) = 0.0 +normal_vector_b(2) = 0.0 // Power conversion efficiency cell_efficiency = 0.3 @@ -49,13 +49,13 @@ number_of_parallel = 1 [SAP3] prescaler = 10 -// Area of a solar cell [m^2] -cell_area = 0.0026 +// Area of a solar cell [m2] +cell_area_m2 = 0.0026 -// Normal vector -normal_vector(0) = -1.0 -normal_vector(1) = 0.0 -normal_vector(2) = 0.0 +// Normal vector at body fixed frame +normal_vector_b(0) = -1.0 +normal_vector_b(1) = 0.0 +normal_vector_b(2) = 0.0 // Power conversion efficiency cell_efficiency = 0.3 @@ -67,4 +67,4 @@ transmission_efficiency = 0.8 number_of_series = 7 // Number of parallel of SAP -number_of_parallel = 1 \ No newline at end of file +number_of_parallel = 1 diff --git a/src/Component/Power/InitSap.cpp b/src/Component/Power/InitSap.cpp index 827226b9b..5dd8be6e0 100644 --- a/src/Component/Power/InitSap.cpp +++ b/src/Component/Power/InitSap.cpp @@ -29,10 +29,10 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons number_of_parallel = sap_conf.ReadInt(Section, "number_of_parallel"); double cell_area; - cell_area = sap_conf.ReadDouble(Section, "cell_area"); + cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); Vector<3> normal_vector; - sap_conf.ReadVector(Section, "normal_vector", normal_vector); + sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); double cell_efficiency; cell_efficiency = sap_conf.ReadDouble(Section, "cell_efficiency"); @@ -65,10 +65,10 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons number_of_parallel = sap_conf.ReadInt(Section, "number_of_parallel"); double cell_area; - cell_area = sap_conf.ReadDouble(Section, "cell_area"); + cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); Vector<3> normal_vector; - sap_conf.ReadVector(Section, "normal_vector", normal_vector); + sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); double cell_efficiency; cell_efficiency = sap_conf.ReadDouble(Section, "cell_efficiency"); From af837584d78c9ddb907347f9c981b88b2216b8fa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:00:51 +0100 Subject: [PATCH 0070/1086] Fix ini file name --- data/sample/initialize_files/sample_satellite.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index 015e5b9ca..f0879c1b4 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -144,5 +144,5 @@ magetorquer_file = ../../data/sample/initialize_files/components/magnetorquer.in rw_file = ../../data/sample/initialize_files/components/reaction_wheel.ini thruster_file = ../../data/sample/initialize_files/components/thruster.ini force_generator_file = ../../data/sample/initialize_files/components/force_generator.ini -torque_generator_file = ../../data/sample/initialize_files/components/torqueGenerator.ini +torque_generator_file = ../../data/sample/initialize_files/components/torque_generator.ini antenna_file = ../../data/sample/initialize_files/components/spacecraft_antenna.ini From 950205029e125b3b8876a70f4529aed81310fc6f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:02:12 +0100 Subject: [PATCH 0071/1086] Fix initialize file name for RW disturbance CSV --- data/sample/initialize_files/components/reaction_wheel.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/components/reaction_wheel.ini b/data/sample/initialize_files/components/reaction_wheel.ini index 629b52ed1..d24180a7d 100644 --- a/data/sample/initialize_files/components/reaction_wheel.ini +++ b/data/sample/initialize_files/components/reaction_wheel.ini @@ -51,8 +51,8 @@ angular_velocity_init = 0.0 //Parameters for calculate RW jitter jitter_calculation = DISABLE jitter_logging = DISABLE -radial_force_harmonics_coef_path = ../../data/SampleSat/ini/component/RWDisturbance/radial_force_harmonics_coef.csv -radial_torque_harmonics_coef_path = ../../data/SampleSat/ini/component/RWDisturbance/radial_torque_harmonics_coef.csv +radial_force_harmonics_coef_path = ../../data/sample/initialize_files/components/rw_disturbance/radial_force_harmonics_coefficients.csv +radial_torque_harmonics_coef_path = ../../data/sample/initialize_files/components/rw_disturbance/radial_torque_harmonics_coefficients.csv harmonics_degree = 12 considers_structural_resonance = DISABLE structural_resonance_freq = 585.0 //[Hz] From 23a912bc16939703864a12259154bfdbda9a6bb2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:21:17 +0100 Subject: [PATCH 0072/1086] fix initialize file for GNSS-R --- .../components/gnss_receiver.ini | 28 +++++++++---------- src/Component/AOCS/InitGnssReceiver.cpp | 10 +++---- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/data/sample/initialize_files/components/gnss_receiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini index 30dd9af06..41197c32a 100644 --- a/data/sample/initialize_files/components/gnss_receiver.ini +++ b/data/sample/initialize_files/components/gnss_receiver.ini @@ -2,15 +2,15 @@ prescaler = 10 // Position of antenna at body frame [m] -antenna_pos_b(0) = 0.0125 -antenna_pos_b(1) = 0.0000 -antenna_pos_b(2) = 0.1815 +antenna_position_b_m(0) = 0.0125 +antenna_position_b_m(1) = 0.0000 +antenna_position_b_m(2) = 0.1815 // Quaternion from body frame to component frame -q_b2c(0) = 0.0 -q_b2c(1) = 0.0 -q_b2c(2) = 0.0 -q_b2c(3) = 1.0 +quaternion_b2c(0) = 0.0 +quaternion_b2c(1) = 0.0 +quaternion_b2c(2) = 0.0 +quaternion_b2c(3) = 1.0 // Antenna model // 0... simple model : GNSS sats are visible when antenna directs anti-earth direction @@ -18,10 +18,10 @@ q_b2c(3) = 1.0 antenna_model = 0 // Antenna half width [deg] -half_width = 60 +antenna_half_width_deg = 60 // Number of channels -ch_max = 8 +maximum_channel = 8 // GNSS ID // G...GPS @@ -34,10 +34,10 @@ ch_max = 8 gnss_id = G //Random noise [m] -nr_stddev_eci(0) = 10000.0 -nr_stddev_eci(1) = 1000.0 -nr_stddev_eci(2) = 1000.0 +white_noise_standard_deviation_eci_m(0) = 10000.0 +white_noise_standard_deviation_eci_m(1) = 1000.0 +white_noise_standard_deviation_eci_m(2) = 1000.0 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 +assumed_power_consumption_W = 1.0 diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index 105af8e69..980ba0b5a 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -37,12 +37,12 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli gnssreceiver_param.antenna_model = SIMPLE; } - gnssr_conf.ReadVector(GSection, "antenna_pos_b", gnssreceiver_param.antenna_pos_b); - gnssr_conf.ReadQuaternion(GSection, "q_b2c", gnssreceiver_param.q_b2c); - gnssreceiver_param.half_width = gnssr_conf.ReadDouble(GSection, "half_width"); + gnssr_conf.ReadVector(GSection, "antenna_position_b_m", gnssreceiver_param.antenna_pos_b); + gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnssreceiver_param.q_b2c); + gnssreceiver_param.half_width = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); gnssreceiver_param.gnss_id = gnssr_conf.ReadString(GSection, "gnss_id"); - gnssreceiver_param.ch_max = gnssr_conf.ReadInt(GSection, "ch_max"); - gnssr_conf.ReadVector(GSection, "nr_stddev_eci", gnssreceiver_param.noise_std); + gnssreceiver_param.ch_max = gnssr_conf.ReadInt(GSection, "maximum_channel"); + gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnssreceiver_param.noise_std); return gnssreceiver_param; } From fc5423e1ba3bdabec8183207ccab541fe754e0d7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:34:41 +0100 Subject: [PATCH 0073/1086] fix initialize file for ground station --- .../components/ground_station_antenna.ini | 26 +++++++++---------- .../components/ground_station_calculator.ini | 16 ++++++------ .../components/spacecraft_antenna.ini | 26 +++++++++---------- src/Component/CommGS/InitAntenna.cpp | 20 +++++++------- src/Component/CommGS/InitGsCalculator.cpp | 16 ++++++------ 5 files changed, 52 insertions(+), 52 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index 87a2776fd..13afaca41 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -2,10 +2,10 @@ // Example of antenna on ground station // Quaternion converts body-fixed frame to component frame -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 +quaternion_b2c(0) = 0 +quaternion_b2c(1) = 0 +quaternion_b2c(2) = 0 +quaternion_b2c(3) = 1 // Flag for transmitter or not is_transmitter = 0 @@ -14,17 +14,17 @@ is_transmitter = 0 is_receiver = 1 // frequency [MHz] -frequency = 8200.0 +frequency_MHz = 8200.0 // Parameters for transmitter // RF output power [W] -tx_output = 1.0 +tx_output_W = 1.0 // Feeder loss [dB] -tx_loss_feeder = -1.5 +tx_loss_feeder_dB = -1.5 // Pointing loss [dB] -tx_loss_pointing = 0.0 +tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna @@ -33,7 +33,7 @@ tx_antenna_gain_model = ISOTROPIC // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis -tx_gain = 12.0 +tx_gain_dBi = 12.0 // Antenna radiation pattern CSV file path tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv @@ -46,13 +46,13 @@ tx_phi_max_rad = 3.14 // Parameters for receiver // Feeder loss [dB] -rx_loss_feeder = -0.5 +rx_loss_feeder_dB = -0.5 // Pointing loss [dB] -rx_loss_pointing = -0.5 +rx_loss_pointing_dB = -0.5 // System noise temperature [K] -rx_system_noise_temperature = 230 +rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna @@ -61,7 +61,7 @@ rx_antenna_gain_model = ISOTROPIC // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis -rx_gain = 43.27 +rx_gain_dBi = 43.27 // Antenna radiation pattern CSV file path rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv diff --git a/data/sample/initialize_files/components/ground_station_calculator.ini b/data/sample/initialize_files/components/ground_station_calculator.ini index 4681a09db..ff280adcf 100644 --- a/data/sample/initialize_files/components/ground_station_calculator.ini +++ b/data/sample/initialize_files/components/ground_station_calculator.ini @@ -1,27 +1,27 @@ [GScalculator] // Polarization loss [dB] -loss_polarization = 0.0 +loss_polarization_dB = 0.0 // Atmospheric loss [dB] -loss_atmosphere = -0.5 +loss_atmosphere_dB = -0.5 // Rain fall loss [dB] -loss_rainfall = -0.12 +loss_rainfall_dB = -0.12 // Other losses [dB] -loss_others = 0.0 +loss_others_dB = 0.0 // Required Eb/N0 [dB](The following value is QPSK and BER=1e-6) -EbN0 = 10.8 +ebn0_dB = 10.8 // Deterioration of hardware [dB] -hardware_deterioration = 1.5 +hardware_deterioration_dB = 1.5 // Codig gain [dB](The following value is RS(E16)+Convolution and BER=1e-6) -coding_gain = -8.17 +coding_gain_dB = -8.17 // Required margin to calclate maximum bitrate [dB] -margin_req = 3.0 +margin_requirement_dB = 3.0 // Downlink bitrate to calculate receive margin [bps] downlink_bitrate_bps = 100000 diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 3e9a10ba4..3228e6347 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -2,10 +2,10 @@ // Example of antenna on spacecraft // Quaternion converts body-fixed frame to component frame -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 +quaternion_b2c(0) = 0 +quaternion_b2c(1) = 0 +quaternion_b2c(2) = 0 +quaternion_b2c(3) = 1 // Flag for transmitter or not is_transmitter = 1 @@ -14,17 +14,17 @@ is_transmitter = 1 is_receiver = 1 // frequency [MHz] -frequency = 8200.0 +frequency_MHz = 8200.0 // Parameters for transmitter // RF output power [W] -tx_output = 1.0 +tx_output_W = 1.0 // Feeder loss [dB] -tx_loss_feeder = -1.5 +tx_loss_feeder_dB = -1.5 // Pointing loss [dB] -tx_loss_pointing = 0.0 +tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna @@ -33,7 +33,7 @@ tx_antenna_gain_model = RADIATION_PATTERN_CSV // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis -tx_gain = 8.0 +tx_gain_dBi = 8.0 // Antenna radiation pattern CSV file path tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv @@ -46,13 +46,13 @@ tx_phi_max_rad = 3.14 // Parameters for receiver // Feeder loss [dB] -rx_loss_feeder = -0.5 +rx_loss_feeder_dB = -0.5 // Pointing loss [dB] -rx_loss_pointing = -0.5 +rx_loss_pointing_dB = -0.5 // System noise temperature [K] -rx_system_noise_temperature = 230 +rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna @@ -61,7 +61,7 @@ rx_antenna_gain_model = RADIATION_PATTERN_CSV // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis -rx_gain = 43.27 +rx_gain_dBi = 43.27 // Antenna radiation pattern CSV file path rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/Component/CommGS/InitAntenna.cpp index 850d985b0..09f87fcd3 100644 --- a/src/Component/CommGS/InitAntenna.cpp +++ b/src/Component/CommGS/InitAntenna.cpp @@ -24,20 +24,20 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { strcat(Section, cs); Quaternion q_b2c; - antenna_conf.ReadQuaternion(Section, "q_b2c", q_b2c); + antenna_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); bool is_transmitter = antenna_conf.ReadBoolean(Section, "is_transmitter"); bool is_receiver = antenna_conf.ReadBoolean(Section, "is_receiver"); - double frequency = antenna_conf.ReadDouble(Section, "frequency"); + double frequency = antenna_conf.ReadDouble(Section, "frequency_MHz"); - double tx_output_power_W = antenna_conf.ReadDouble(Section, "tx_output"); - double rx_system_noise_temperature_K = antenna_conf.ReadDouble(Section, "rx_system_noise_temperature"); + double tx_output_power_W = antenna_conf.ReadDouble(Section, "tx_output_W"); + double rx_system_noise_temperature_K = antenna_conf.ReadDouble(Section, "rx_system_noise_temperature_K"); AntennaParameters tx_params; if (is_transmitter) { - tx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "tx_gain"); - tx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_feeder"); - tx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_pointing"); + tx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "tx_gain_dBi"); + tx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_feeder_dB"); + tx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_pointing_dB"); tx_params.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "tx_antenna_gain_model")); size_t length_theta = antenna_conf.ReadInt(Section, "tx_length_theta"); size_t length_phi = antenna_conf.ReadInt(Section, "tx_length_phi"); @@ -54,9 +54,9 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { AntennaParameters rx_params; if (is_receiver) { - rx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "rx_gain"); - rx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_feeder"); - rx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_pointing"); + rx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "rx_gain_dBi"); + rx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_feeder_dB"); + rx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_pointing_dB"); rx_params.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "rx_antenna_gain_model")); rx_params.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "rx_antenna_radiation_pattern_file")); size_t length_theta = antenna_conf.ReadInt(Section, "rx_length_theta"); diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/Component/CommGS/InitGsCalculator.cpp index b9c8c2233..87583fc1a 100644 --- a/src/Component/CommGS/InitGsCalculator.cpp +++ b/src/Component/CommGS/InitGsCalculator.cpp @@ -19,14 +19,14 @@ GScalculator InitGScalculator(const std::string fname) { char Section[30] = "GScalculator"; // strcat(Section, cs); - double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization"); - double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere"); - double loss_rainfall = gs_conf.ReadDouble(Section, "loss_rainfall"); - double loss_others = gs_conf.ReadDouble(Section, "loss_others"); - double EbN0 = gs_conf.ReadDouble(Section, "EbN0"); - double hardware_deterioration = gs_conf.ReadDouble(Section, "hardware_deterioration"); - double coding_gain = gs_conf.ReadDouble(Section, "coding_gain"); - double margin_req = gs_conf.ReadDouble(Section, "margin_req"); + double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization_dB"); + double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere_dB"); + double loss_rainfall = gs_conf.ReadDouble(Section, "loss_rainfall_dB"); + double loss_others = gs_conf.ReadDouble(Section, "loss_others_dB"); + double EbN0 = gs_conf.ReadDouble(Section, "ebn0_dB"); + double hardware_deterioration = gs_conf.ReadDouble(Section, "hardware_deterioration_dB"); + double coding_gain = gs_conf.ReadDouble(Section, "coding_gain_dB"); + double margin_req = gs_conf.ReadDouble(Section, "margin_requirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); GScalculator gs_calculator(loss_polarization, loss_atmosphere, loss_rainfall, loss_others, EbN0, hardware_deterioration, coding_gain, margin_req, From 22780f5ca6ba000b9ffc172b3877519d236fe6de Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 11:39:45 +0100 Subject: [PATCH 0074/1086] Fix initialize file for thruster --- .../initialize_files/components/thruster.ini | 22 +++++++++---------- .../Propulsion/InitSimpleThruster.cpp | 20 ++++++++--------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/data/sample/initialize_files/components/thruster.ini b/data/sample/initialize_files/components/thruster.ini index 8af3ae449..c2b752e3e 100644 --- a/data/sample/initialize_files/components/thruster.ini +++ b/data/sample/initialize_files/components/thruster.ini @@ -2,24 +2,24 @@ prescaler = 10; // Position of thruster head at body frame [m] -thruster_pos(0) = 0.0125 -thruster_pos(1) = 0.0000 -thruster_pos(2) = -0.1815 +thruster_position_b_m(0) = 0.0125 +thruster_position_b_m(1) = 0.0000 +thruster_position_b_m(2) = -0.1815 // Thrust direction vector at body frame [m] -thruster_dir(0) = 0 -thruster_dir(1) = 0 -thruster_dir(2) = 1 +thruster_direction_b(0) = 0 +thruster_direction_b(1) = 0 +thruster_direction_b(2) = 1 // Maximum thrust [N] -max_mag = 0.050 +thrust_magnitude_N = 0.050 // Standard deviation of thrust error [N] -mag_err = 0.001 +thrust_error_standard_deviation_N = 0.001 // Standard deviation of thrust direction error [deg] -dir_err = 1 +direction_error_standard_deviation_deg = 1 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 +assumed_power_consumption_W = 1.0 diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 32f5d5b70..14ab13e1b 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -18,18 +18,18 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co if (prescaler <= 1) prescaler = 1; Vector<3> thruster_pos; - thruster_conf.ReadVector(Section, "thruster_pos", thruster_pos); + thruster_conf.ReadVector(Section, "thruster_position_b_m", thruster_pos); Vector<3> thruster_dir; - thruster_conf.ReadVector(Section, "thruster_dir", thruster_dir); + thruster_conf.ReadVector(Section, "thruster_direction_b", thruster_dir); - double max_mag = thruster_conf.ReadDouble(Section, "max_mag"); + double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); double mag_err; - mag_err = thruster_conf.ReadDouble(Section, "mag_err"); + mag_err = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); double deg_err; - deg_err = thruster_conf.ReadDouble(Section, "dir_err") * libra::pi / 180.0; + deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; SimpleThruster thruster(prescaler, clock_gen, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); return thruster; @@ -45,18 +45,18 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_po if (prescaler <= 1) prescaler = 1; Vector<3> thruster_pos; - thruster_conf.ReadVector(Section, "thruster_pos", thruster_pos); + thruster_conf.ReadVector(Section, "thruster_position_b_m", thruster_pos); Vector<3> thruster_dir; - thruster_conf.ReadVector(Section, "thruster_dir", thruster_dir); + thruster_conf.ReadVector(Section, "thruster_direction_b", thruster_dir); - double max_mag = thruster_conf.ReadDouble(Section, "max_mag"); + double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); double mag_err; - mag_err = thruster_conf.ReadDouble(Section, "mag_err"); + mag_err = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); double deg_err; - deg_err = thruster_conf.ReadDouble(Section, "dir_err") * libra::pi / 180.0; + deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; SimpleThruster thruster(prescaler, clock_gen, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); return thruster; From 97f76e04fec26df1d51cffa7ad030e8037483efa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 12:55:55 +0100 Subject: [PATCH 0075/1086] Fix initialize file for telescope --- .../initialize_files/components/telescope.ini | 70 +++++++++---------- .../Mission/Telescope/InitTelescope.cpp | 18 ++--- 2 files changed, 43 insertions(+), 45 deletions(-) diff --git a/data/sample/initialize_files/components/telescope.ini b/data/sample/initialize_files/components/telescope.ini index 8cd3aea09..78bb71124 100644 --- a/data/sample/initialize_files/components/telescope.ini +++ b/data/sample/initialize_files/components/telescope.ini @@ -1,37 +1,35 @@ [Telescope1] -//@̍Wn(B)]Wn(C)ϊQuaternion,(C̏)C]Wn͎X -//C[WZTXR|WZAC[WZTYR|WYɂȂ悤ɒ` -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 - -//z֎~p[deg]ApŒ` -// [0,90]͈̔͂Őݒ -sun_forbidden_angle = 60 - -//n֎~p[deg]ApŒ` -// [0,90]͈̔͂Őݒ -earth_forbidden_angle = 60 - -//֎~p[deg]ApŒ` -// [0,90]͈̔͂Őݒ -moon_forbidden_angle = 60 - -//xf[] -x_num_of_pix = 2048 - -//yf[] -y_num_of_pix = 2048 - -//x1sNZ莋p[deg]ApŒ` -//xfƂ̐ς[0,90]͈̔͂ɂ邱ƂKmF -x_fov_par_pix = 0.02 - -//y1sNZ莋p[deg]ApŒ` -//yfƂ̐ς[0,90]͈̔͂ɂ邱ƂKmF -y_fov_par_pix = 0.02 - -//Oɏo͂P̌ -//ɓĂP̂A邢̂珇ԂɁAŎw肵o͂ -num_of_logged_stars = 3 \ No newline at end of file +// Frame conversion quaternion from body-fixed frame to component frame +// +X axis of the component frame: Line of sight direction +// +Y axis of the component frame: +Y axis of the image sensor +// +Z axis of the component frame: +Z axis of the image sensor +quaternion_b2c(0) = 0 +quaternion_b2c(1) = 0 +quaternion_b2c(2) = 0 +quaternion_b2c(3) = 1 + +// Sun forbidden angle [0, 90] +sun_forbidden_angle_deg = 60 + +// Earth forbidden angle [0, 90] +earth_forbidden_angle_deg = 60 + +// Moon forbidden angle [0, 90] +moon_forbidden_angle_deg = 60 + +// Number of pixel in the X direction of image sensor +x_number_of_pixel = 2048 + +// Number of pixel in the Y direction of image sensor +y_number_of_pixel = 2048 + +// Field of View(FoV) angle per pixel in the X direction of image sensor +// x_number_of_pixel * x_fov_deg_per_pixel should be smallser than 90 deg. +x_fov_deg_per_pixel = 0.02 + +// Field of View(FoV) angle per pixel in the Y direction of image sensor +// y_number_of_pixel * y_fov_deg_per_pixel should be smallser than 90 deg. +y_fov_deg_per_pixel = 0.02 + +// Number of stars to show log output +number_of_stars_for_log = 3 diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index bf0d09ec9..f14d67c79 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -29,24 +29,24 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string f #endif Quaternion q_b2c; - Telescope_conf.ReadQuaternion(TelescopeSection, "q_b2c", q_b2c); + Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", q_b2c); - double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_forbidden_angle"); + double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_forbidden_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * pi / 180; // deg to rad - double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_forbidden_angle"); + double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_forbidden_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * pi / 180; // deg to rad - double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_forbidden_angle"); + double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_forbidden_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * pi / 180; // deg to rad - int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_num_of_pix"); - int y_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_num_of_pix"); + int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); + int y_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_number_of_pixel"); - double x_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_par_pix"); + double x_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_deg_per_pixel"); double x_fov_par_pix_rad = x_fov_par_pix_deg * pi / 180; // deg to rad - double y_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_par_pix"); + double y_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_deg_per_pixel"); double y_fov_par_pix_rad = y_fov_par_pix_deg * pi / 180; // deg to rad - int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "num_of_logged_stars"); + int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); Telescope telescope(clock_gen, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); From cae7071248f49ea2e3c60f7ff4baf1a58d732738 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 13:00:56 +0100 Subject: [PATCH 0076/1086] Fix initialize for sun sensors --- .../components/sun_sensor.ini | 24 +++++++++---------- src/Component/AOCS/InitSunSensor.cpp | 16 ++++++------- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/data/sample/initialize_files/components/sun_sensor.ini b/data/sample/initialize_files/components/sun_sensor.ini index 4bf7f334b..a84bb5f89 100644 --- a/data/sample/initialize_files/components/sun_sensor.ini +++ b/data/sample/initialize_files/components/sun_sensor.ini @@ -3,19 +3,19 @@ prescaler = 10; // Quaternion from body frame to component frame // The sight direction is Z-axis at the component frame -q_b2c(0) = 0.0 -q_b2c(1) = 0.0 -q_b2c(2) = 0.0 -q_b2c(3) = 1.0 +quaternion_b2c(0) = 0.0 +quaternion_b2c(1) = 0.0 +quaternion_b2c(2) = 0.0 +quaternion_b2c(3) = 1.0 -//FoV [deg] -detectable_angle_deg = 55.0 +// Field of View [deg] +field_of_view_deg = 55.0 -//Standard deviation of normal noise[deg] -nr_stddev = 0.5 +// Standard deviation of normal noise[deg] +white_noise_standard_deviation_deg = 0.5 -//Standard deviation of bias noise[deg] -nr_bias_stddev = 0.5 +// Standard deviation of bias noise[deg] +bias_standard_deviation_deg = 0.5 // Threshold of light-receiving intensity[%] // Defined as a percentage to the solar constant @@ -23,5 +23,5 @@ nr_bias_stddev = 0.5 intensity_lower_threshold_percent = 30.0 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 +assumed_power_consumption_W = 1.0 diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index 65d559910..3df68b0f9 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -21,18 +21,18 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n if (prescaler <= 1) prescaler = 1; Quaternion q_b2c; - ss_conf.ReadQuaternion(Section, "q_b2c", q_b2c); + ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; - detectable_angle_deg = ss_conf.ReadDouble(Section, "detectable_angle_deg"); + detectable_angle_deg = ss_conf.ReadDouble(Section, "field_of_view_deg"); detectable_angle_rad = libra::pi / 180.0 * detectable_angle_deg; double nr_stddev = 0.0; - nr_stddev = ss_conf.ReadDouble(Section, "nr_stddev"); + nr_stddev = ss_conf.ReadDouble(Section, "white_noise_standard_deviation_deg"); nr_stddev *= libra::pi / 180.0; double nr_bias_stddev = 0.0; - nr_bias_stddev = ss_conf.ReadDouble(Section, "nr_bias_stddev"); + nr_bias_stddev = ss_conf.ReadDouble(Section, "bias_standard_deviation_deg"); nr_bias_stddev *= libra::pi / 180.0; double intensity_lower_threshold_percent; @@ -54,18 +54,18 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss if (prescaler <= 1) prescaler = 1; Quaternion q_b2c; - ss_conf.ReadQuaternion(Section, "q_b2c", q_b2c); + ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; - detectable_angle_deg = ss_conf.ReadDouble(Section, "detectable_angle_deg"); + detectable_angle_deg = ss_conf.ReadDouble(Section, "field_of_view_deg"); detectable_angle_rad = libra::pi / 180.0 * detectable_angle_deg; double nr_stddev = 0.0; - nr_stddev = ss_conf.ReadDouble(Section, "nr_stddev"); + nr_stddev = ss_conf.ReadDouble(Section, "white_noise_standard_deviation_deg"); nr_stddev *= libra::pi / 180.0; double nr_bias_stddev = 0.0; - nr_bias_stddev = ss_conf.ReadDouble(Section, "nr_bias_stddev"); + nr_bias_stddev = ss_conf.ReadDouble(Section, "bias_standard_deviation_deg"); nr_bias_stddev *= libra::pi / 180.0; double intensity_lower_threshold_percent; From de0c1443a47d0e6af172dfddccf8c40afafee064 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 13:05:35 +0100 Subject: [PATCH 0077/1086] Fix initialize for star sensor --- .../components/star_sensor.ini | 28 +++++++-------- src/Component/AOCS/InitStt.cpp | 36 +++++++++---------- 2 files changed, 32 insertions(+), 32 deletions(-) diff --git a/data/sample/initialize_files/components/star_sensor.ini b/data/sample/initialize_files/components/star_sensor.ini index 503f0c3b0..b9d531cbe 100644 --- a/data/sample/initialize_files/components/star_sensor.ini +++ b/data/sample/initialize_files/components/star_sensor.ini @@ -3,35 +3,35 @@ prescaler = 10; // Quaternion from body frame to component frame // The sight direction is X-axis at component frame -q_b2c(0) = 0 -q_b2c(1) = 0 -q_b2c(2) = 0 -q_b2c(3) = 1 +quaternion_b2c(0) = 0 +quaternion_b2c(1) = 0 +quaternion_b2c(2) = 0 +quaternion_b2c(3) = 1 // Standard deviation of normal random noise at orthogonal direction of sight[rad] -sigma_ortho = 0 +standard_deviation_orthogonal_direction_rad = 0 // Standard deviation of normal random noise at sight direction [rad] -sigma_sight = 0 +standard_deviation_sight_direction_rad = 0 // Output delay [sec] -output_delay = 1 +output_delay_s = 1 // Output Interval [sec] -output_interval = 1 +output_interval_s = 1 // Sun forbidden harf angle [deg] -sun_forbidden_angle = 10 +sun_forbidden_angle_deg = 10 // Earth forbidden harf angle [deg] -earth_forbidden_angle = 10 +earth_forbidden_angle_deg = 10 // Moon forbidden harf angle [deg] -moon_forbidden_angle = 10 +moon_forbidden_angle_deg = 10 // Limit angular rate to capture stars[deg/s] -capture_rate = 10.0 +angular_rate_limit_deg_s = 10.0 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 // V +assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index ca7b577df..1b4c4b673 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -20,20 +20,20 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double if (prescaler <= 1) prescaler = 1; double step_time = compo_step_time * prescaler; Quaternion q_b2c; - STT_conf.ReadQuaternion(STTSection, "q_b2c", q_b2c); - double sigma_ortho = STT_conf.ReadDouble(STTSection, "sigma_ortho"); - double sigma_sight = STT_conf.ReadDouble(STTSection, "sigma_sight"); - double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay"); + STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", q_b2c); + double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); + double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); + double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); int output_delay = max(int(output_delay_sec / step_time), 1); - double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval"); + double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); int output_interval = max(int(output_interval_sec / step_time), 1); - double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle"); + double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; - double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle"); + double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * libra::pi / 180.0; - double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle"); + double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * libra::pi / 180.0; - double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "capture_rate"); + double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; STT stt(prescaler, clock_gen, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, @@ -52,20 +52,20 @@ STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, con double step_time = compo_step_time * prescaler; Quaternion q_b2c; - STT_conf.ReadQuaternion(STTSection, "q_b2c", q_b2c); - double sigma_ortho = STT_conf.ReadDouble(STTSection, "sigma_ortho"); - double sigma_sight = STT_conf.ReadDouble(STTSection, "sigma_sight"); - double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay"); + STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", q_b2c); + double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); + double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); + double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); int output_delay = max(int(output_delay_sec / step_time), 1); - double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval"); + double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); int output_interval = max(int(output_interval_sec / step_time), 1); - double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle"); + double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; - double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle"); + double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * libra::pi / 180.0; - double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle"); + double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * libra::pi / 180.0; - double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "capture_rate"); + double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; STT stt(prescaler, clock_gen, power_port, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, From 1bb009b31ecd12d306130d63ed8334a1a78f6dc3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 13:21:56 +0100 Subject: [PATCH 0078/1086] Fix initialize file for magnetorquer --- .../components/magnetorquer.ini | 66 +++++++++---------- src/Component/AOCS/InitMagTorquer.cpp | 36 +++++----- .../SampleSpacecraft/SampleComponents.cpp | 2 +- 3 files changed, 52 insertions(+), 52 deletions(-) diff --git a/data/sample/initialize_files/components/magnetorquer.ini b/data/sample/initialize_files/components/magnetorquer.ini index c501e2ec7..ad6fbad5c 100644 --- a/data/sample/initialize_files/components/magnetorquer.ini +++ b/data/sample/initialize_files/components/magnetorquer.ini @@ -2,53 +2,53 @@ prescaler = 10 //Quaternion from body frame to component frame -q_b2c(0) = 0.0 -q_b2c(1) = 0.0 -q_b2c(2) = 0.0 -q_b2c(3) = 1.0 +quaternion_b2c(0) = 0.0 +quaternion_b2c(1) = 0.0 +quaternion_b2c(2) = 0.0 +quaternion_b2c(3) = 1.0 // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), -ScaleFactor(0) = 1.0 -ScaleFactor(1) = 0.0 -ScaleFactor(2) = 0.0 -ScaleFactor(3) = 0.0 -ScaleFactor(4) = 1.0 -ScaleFactor(5) = 0.0 -ScaleFactor(6) = 0.0 -ScaleFactor(7) = 0.0 -ScaleFactor(8) = 1.0 +scale_factor_c(0) = 1.0 +scale_factor_c(1) = 0.0 +scale_factor_c(2) = 0.0 +scale_factor_c(3) = 0.0 +scale_factor_c(4) = 1.0 +scale_factor_c(5) = 0.0 +scale_factor_c(6) = 0.0 +scale_factor_c(7) = 0.0 +scale_factor_c(8) = 1.0 // Maximum magnetic moment on component frame [Am^2] -Max_c(0) = 0.1 -Max_c(1) = 0.1 -Max_c(2) = 0.1 +max_output_magnetic_moment_c_Am2(0) = 0.1 +max_output_magnetic_moment_c_Am2(1) = 0.1 +max_output_magnetic_moment_c_Am2(2) = 0.1 // Minimum magnetic moment on component frame [Am^2] -Min_c(0) = -0.1 -Min_c(1) = -0.1 -Min_c(2) = -0.1 +min_output_magnetic_moment_c_Am2(0) = -0.1 +min_output_magnetic_moment_c_Am2(1) = -0.1 +min_output_magnetic_moment_c_Am2(2) = -0.1 // Constant bias noise on component frame [Am^2] -Bias_c(0) = 0.0 -Bias_c(1) = 0.0 -Bias_c(2) = 0.0 +constant_bias_noise_c_Am2(0) = 0.0 +constant_bias_noise_c_Am2(1) = 0.0 +constant_bias_noise_c_Am2(2) = 0.0 // Standard deviation for random walk noise[Am^2] -rw_stddev_c(0) = 0.0 -rw_stddev_c(1) = 0.0 -rw_stddev_c(2) = 0.0 +random_walk_standard_deviation_c_Am2(0) = 0.0 +random_walk_standard_deviation_c_Am2(1) = 0.0 +random_walk_standard_deviation_c_Am2(2) = 0.0 // Limit of random walk noise[Am^2] -rw_limit_c(0) = 0.0 -rw_limit_c(1) = 0.0 -rw_limit_c(2) = 0.0 +random_walk_limit_c_Am2(0) = 0.0 +random_walk_limit_c_Am2(1) = 0.0 +random_walk_limit_c_Am2(2) = 0.0 // Standard deviation of normal random noise[Am^2] -nr_stddev_c(0) = 0.0 -nr_stddev_c(1) = 0.0 -nr_stddev_c(2) = 0.0 +white_noise_standard_deviation_c_Am2(0) = 0.0 +white_noise_standard_deviation_c_Am2(1) = 0.0 +white_noise_standard_deviation_c_Am2(2) = 0.0 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 // V +assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index 2750eed5b..c38d9ecd4 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -15,7 +15,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: if (prescaler <= 1) prescaler = 1; Vector sf_vec; - magtorquer_conf.ReadVector(MTSection, "ScaleFactor", sf_vec); + magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); Matrix scale_factor; for (size_t i = 0; i < kMtqDim; i++) { for (size_t j = 0; j < kMtqDim; j++) { @@ -24,24 +24,24 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: } Quaternion q_b2c; - magtorquer_conf.ReadQuaternion(MTSection, "q_b2c", q_b2c); + magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", q_b2c); Vector max_c; - magtorquer_conf.ReadVector(MTSection, "Max_c", max_c); + magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); Vector min_c; - magtorquer_conf.ReadVector(MTSection, "Min_c", min_c); + magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_c); Vector bias_c; - magtorquer_conf.ReadVector(MTSection, "Bias_c", bias_c); + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_c); double rw_stepwidth = compo_step_time * (double)prescaler; Vector rw_stddev_c; - magtorquer_conf.ReadVector(MTSection, "rw_stddev_c", rw_stddev_c); + magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", rw_stddev_c); Vector rw_limit_c; - magtorquer_conf.ReadVector(MTSection, "rw_limit_c", rw_limit_c); + magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", rw_limit_c); Vector nr_stddev_c; - magtorquer_conf.ReadVector(MTSection, "nr_stddev_c", nr_stddev_c); + magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); MagTorquer magtorquer(prescaler, clock_gen, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); @@ -57,7 +57,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int if (prescaler <= 1) prescaler = 1; Vector sf_vec; - magtorquer_conf.ReadVector(MTSection, "ScaleFactor", sf_vec); + magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); Matrix scale_factor; for (size_t i = 0; i < kMtqDim; i++) { for (size_t j = 0; j < kMtqDim; j++) { @@ -66,29 +66,29 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int } Quaternion q_b2c; - magtorquer_conf.ReadQuaternion(MTSection, "q_b2c", q_b2c); + magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", q_b2c); Vector max_c; - magtorquer_conf.ReadVector(MTSection, "Max_c", max_c); + magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); Vector min_c; - magtorquer_conf.ReadVector(MTSection, "Min_c", min_c); + magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_c); Vector bias_c; - magtorquer_conf.ReadVector(MTSection, "Bias_c", bias_c); + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_c); double rw_stepwidth = compo_step_time * (double)prescaler; Vector rw_stddev_c; - magtorquer_conf.ReadVector(MTSection, "rw_stddev_c", rw_stddev_c); + magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", rw_stddev_c); Vector rw_limit_c; - magtorquer_conf.ReadVector(MTSection, "rw_limit_c", rw_limit_c); + magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", rw_limit_c); Vector nr_stddev_c; - magtorquer_conf.ReadVector(MTSection, "nr_stddev_c", nr_stddev_c); + magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); // PowerPort - double minimum_voltage = magtorquer_conf.ReadDouble(MTSection, "minimum_voltage"); + double minimum_voltage = magtorquer_conf.ReadDouble(MTSection, "minimum_voltage_V"); power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = magtorquer_conf.ReadDouble(MTSection, "assumed_power_consumption"); + double assumed_power_consumption = magtorquer_conf.ReadDouble(MTSection, "assumed_power_consumption_W"); power_port->SetAssumedPowerConsumption(assumed_power_consumption); MagTorquer magtorquer(prescaler, clock_gen, power_port, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp index 4bb70ad8a..05c75365b 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp @@ -52,7 +52,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimTime()))); // MagTorquer - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "mag_torquer_file"); + ini_path = iniAccess.ReadString("COMPONENTS_FILE", "magetorquer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_torquer_ = new MagTorquer( InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); From 95c9c882c61302bb1b6cc4ef884d239e313ffd00 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 13:55:08 +0100 Subject: [PATCH 0079/1086] Fix initialize file for RW --- .../components/reaction_wheel.ini | 67 ++++++++++--------- src/Component/AOCS/InitRwModel.cpp | 26 +++---- 2 files changed, 47 insertions(+), 46 deletions(-) diff --git a/data/sample/initialize_files/components/reaction_wheel.ini b/data/sample/initialize_files/components/reaction_wheel.ini index d24180a7d..d7345cdb8 100644 --- a/data/sample/initialize_files/components/reaction_wheel.ini +++ b/data/sample/initialize_files/components/reaction_wheel.ini @@ -5,13 +5,14 @@ prescaler = 1 // prescaler for calculation of RW jitter // To calculate the jitter, set the update cycle to about 0.1 ms. fast_prescaler = 1 -//Inertia of the RW [kgm^2] -inertia = 1.0e-4 -//Maximum torque [Nm] -max_torque = 0.001 -//Maximum angular velocity [rpm] -//The RW can drive (-max_angular_velocity,+max_angular_velocity) -max_angular_velocity = 6000.0 + +// Moment of inertia of the rotor [kgm^2] +moment_of_inertia_kgm2 = 1.0e-4 +// Maximum torque [Nm] +max_output_torque_Nm = 0.001 +// Maximum angular velocity [rpm] +// The RW can drive (-max_angular_velocity, +max_angular_velocity) +max_angular_velocity_rpm = 6000.0 // How to determine the direction of RW (DIRECTION or QUATERNION) // If you want to consider the phase of RW strictly (e.g. RW jitter), specify QUATERNION. @@ -19,10 +20,10 @@ max_angular_velocity = 6000.0 direction_determination_mode = QUATERNION // Quaternion from body frame to component frame // Definition of component frame : wheel rotation axis = (0 0 1)^T. plus means direction of rotation (output torque is minus direction) -q_b2c(0) = 0 -q_b2c(1) = 0.70710678118 -q_b2c(2) = 0 -q_b2c(3) = 0.70710678118 +quaternion_b2c(0) = 0 +quaternion_b2c(1) = 0.70710678118 +quaternion_b2c(2) = 0 +quaternion_b2c(3) = 0.70710678118 // Direction of axis of the RW at the body fixied frame // plus means direction of rotation (output torque is minus direction) direction_b(0) = 1.0 @@ -30,35 +31,35 @@ direction_b(1) = 0.0 direction_b(2) = 0.0 // Position of RW at body frame [m] -pos_b(0) = 1.0 -pos_b(1) = 0.0 -pos_b(2) = 0.0 -//The control deray[s] -dead_time = 1.0 -//Coefficient of first order lag for driving case -firstorder_lag_coef(0) = 2.0 -firstorder_lag_coef(1) = 0.0 -firstorder_lag_coef(2) = 0.0 -//Coefficient of first order lag for coasting case -coasting_lag_coef(0) = 2.0 -coasting_lag_coef(1) = 0.0 -coasting_lag_coef(2) = 0.0 -//For drive initialize -//They should be zero for normal case -motor_drive_init = 0 -angular_velocity_init = 0.0 +position_b_m(0) = 1.0 +position_b_m(1) = 0.0 +position_b_m(2) = 0.0 +// The control deray[s] +dead_time_s = 1.0 +// Coefficient of first order lag for driving case +first_order_lag_coefficient(0) = 2.0 +first_order_lag_coefficient(1) = 0.0 +first_order_lag_coefficient(2) = 0.0 +// Coefficient of first order lag for coasting case +coasting_lag_coefficient(0) = 2.0 +coasting_lag_coefficient(1) = 0.0 +coasting_lag_coefficient(2) = 0.0 +// For drive initialize +// They should be zero for normal case +initial_motor_drive_flag = 0 +initial_angular_velocity_rad_s = 0.0 //Parameters for calculate RW jitter jitter_calculation = DISABLE jitter_logging = DISABLE -radial_force_harmonics_coef_path = ../../data/sample/initialize_files/components/rw_disturbance/radial_force_harmonics_coefficients.csv -radial_torque_harmonics_coef_path = ../../data/sample/initialize_files/components/rw_disturbance/radial_torque_harmonics_coefficients.csv +radial_force_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance/radial_force_harmonics_coefficients.csv +radial_torque_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance/radial_torque_harmonics_coefficients.csv harmonics_degree = 12 considers_structural_resonance = DISABLE -structural_resonance_freq = 585.0 //[Hz] +structural_resonance_frequency_Hz = 585.0 //[Hz] damping_factor = 0.1 //[ ] bandwidth = 0.001 //[ ] // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W +minimum_voltage_V = 3.3 // V +assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index 6fc48df6e..418614e7e 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -49,14 +49,14 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double if (prescaler <= 1) prescaler = 1; fast_prescaler = rwmodel_conf.ReadInt(RWsection, "fast_prescaler"); if (fast_prescaler <= 1) fast_prescaler = 1; - inertia = rwmodel_conf.ReadDouble(RWsection, "inertia"); - max_torque = rwmodel_conf.ReadDouble(RWsection, "max_torque"); - max_velocity = rwmodel_conf.ReadDouble(RWsection, "max_angular_velocity"); + inertia = rwmodel_conf.ReadDouble(RWsection, "moment_of_inertia_kgm2"); + max_torque = rwmodel_conf.ReadDouble(RWsection, "max_output_torque_Nm"); + max_velocity = rwmodel_conf.ReadDouble(RWsection, "max_angular_velocity_rpm"); std::string direction_determination_mode; direction_determination_mode = rwmodel_conf.ReadString(RWsection, "direction_determination_mode"); if (direction_determination_mode == "QUATERNION") { - rwmodel_conf.ReadQuaternion(RWsection, "q_b2c", q_b2c); + rwmodel_conf.ReadQuaternion(RWsection, "quaternion_b2c", q_b2c); } else // direction_determination_mode == "DIRECTION" { Vector<3> direction_b; @@ -67,29 +67,29 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double q_b2c = q.conjugate(); } - rwmodel_conf.ReadVector(RWsection, "pos_b", pos_b); - dead_time = rwmodel_conf.ReadDouble(RWsection, "dead_time"); - // rwmodel_conf.ReadVector(RWsection, "firstorder_lag_coef", ordinary_lag_coef); // TODO: Fix bug - // rwmodel_conf.ReadVector(RWsection, "coasting_lag_coef", coasting_lag_coef); // TODO: Fix bug + rwmodel_conf.ReadVector(RWsection, "position_b_m", pos_b); + dead_time = rwmodel_conf.ReadDouble(RWsection, "dead_time_s"); + // rwmodel_conf.ReadVector(RWsection, "first_order_lag_coefficient", ordinary_lag_coef); // TODO: Fix bug + // rwmodel_conf.ReadVector(RWsection, "coasting_lag_coefficient", coasting_lag_coef); // TODO: Fix bug is_calc_jitter_enabled = rwmodel_conf.ReadEnable(RWsection, "jitter_calculation"); is_log_jitter_enabled = rwmodel_conf.ReadEnable(RWsection, "jitter_logging"); - std::string radial_force_harmonics_coef_path = rwmodel_conf.ReadString(RWsection, "radial_force_harmonics_coef_path"); - std::string radial_torque_harmonics_coef_path = rwmodel_conf.ReadString(RWsection, "radial_torque_harmonics_coef_path"); + std::string radial_force_harmonics_coef_path = rwmodel_conf.ReadString(RWsection, "radial_force_harmonics_coefficient_file"); + std::string radial_torque_harmonics_coef_path = rwmodel_conf.ReadString(RWsection, "radial_torque_harmonics_coefficient_file"); int harmonics_degree = rwmodel_conf.ReadInt(RWsection, "harmonics_degree"); IniAccess conf_radial_force_harmonics(radial_force_harmonics_coef_path); IniAccess conf_radial_torque_harmonics(radial_torque_harmonics_coef_path); conf_radial_force_harmonics.ReadCsvDouble(radial_force_harmonics_coef, harmonics_degree); conf_radial_torque_harmonics.ReadCsvDouble(radial_torque_harmonics_coef, harmonics_degree); - structural_resonance_freq = rwmodel_conf.ReadDouble(RWsection, "structural_resonance_freq"); + structural_resonance_freq = rwmodel_conf.ReadDouble(RWsection, "structural_resonance_frequency_Hz"); damping_factor = rwmodel_conf.ReadDouble(RWsection, "damping_factor"); bandwidth = rwmodel_conf.ReadDouble(RWsection, "bandwidth"); considers_structural_resonance = rwmodel_conf.ReadEnable(RWsection, "considers_structural_resonance"); - drive_flag = rwmodel_conf.ReadBoolean(RWsection, "motor_drive_init"); - init_velocity = rwmodel_conf.ReadDouble(RWsection, "angular_velocity_init"); + drive_flag = rwmodel_conf.ReadBoolean(RWsection, "initial_motor_drive_flag"); + init_velocity = rwmodel_conf.ReadDouble(RWsection, "initial_angular_velocity_rad_s"); // Calc periods step_width = prop_step; From 7a48702a3d5fc2e9c9e4d499c62c22ec176a6a6f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 14:47:44 +0100 Subject: [PATCH 0080/1086] Fix initialize file for gyro sensor --- .../components/gyro_sensor.ini | 59 +++++++++-------- src/Component/AOCS/InitGyro.cpp | 66 +++---------------- .../Abstract/InitializeSensorBase.hpp | 6 +- .../Abstract/InitializeSensorBase_tfs.hpp | 26 +++++--- 4 files changed, 60 insertions(+), 97 deletions(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index 32286d88b..ce769a504 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -3,47 +3,48 @@ prescaler = 10 // Quaternion from body frame to component frame // Including misalignment -q_b2c(0) = 0.0 -q_b2c(1) = 0.0 -q_b2c(2) = 0.0 -q_b2c(3) = 1.0 +quaternion_b2c(0) = 0.0 +quaternion_b2c(1) = 0.0 +quaternion_b2c(2) = 0.0 +quaternion_b2c(3) = 1.0 +[SensorBaseGyro] // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), -ScaleFactor(0) = 1.0 -ScaleFactor(1) = 0.0 -ScaleFactor(2) = 0.0 -ScaleFactor(3) = 0.0 -ScaleFactor(4) = 1.0 -ScaleFactor(5) = 0.0 -ScaleFactor(6) = 0.0 -ScaleFactor(7) = 0.0 -ScaleFactor(8) = 1.0 +scale_factor_c(0) = 1.0 +scale_factor_c(1) = 0.0 +scale_factor_c(2) = 0.0 +scale_factor_c(3) = 0.0 +scale_factor_c(4) = 1.0 +scale_factor_c(5) = 0.0 +scale_factor_c(6) = 0.0 +scale_factor_c(7) = 0.0 +scale_factor_c(8) = 1.0 // Constant bias noise at component frame [rad/s] -Bias_c(0) = 1.0e-3 -Bias_c(1) = -1.0e-3 -Bias_c(2) = 2.0e-3 +constant_bias_c_rad_s(0) = 1.0e-3 +constant_bias_c_rad_s(1) = -1.0e-3 +constant_bias_c_rad_s(2) = 2.0e-3 // Standard deviation for random walk noise[rad/s] -rw_stddev_c(0) = 0.0 -rw_stddev_c(1) = 0.0 -rw_stddev_c(2) = 0.0 +normal_random_standard_deviation_c_rad_s(0) = 0.0 +normal_random_standard_deviation_c_rad_s(1) = 0.0 +normal_random_standard_deviation_c_rad_s(2) = 0.0 // Limit of random walk noise[rad/s] -rw_limit_c(0) = 0.0 -rw_limit_c(1) = 0.0 -rw_limit_c(2) = 0.0 +random_walk_limit_c_rad_s(0) = 0.0 +random_walk_limit_c_rad_s(1) = 0.0 +random_walk_limit_c_rad_s(2) = 0.0 // Standard deviation of normal random noise[rad/s] -nr_stddev_c(0) = 1e-3 -nr_stddev_c(1) = 1e-3 -nr_stddev_c(2) = 1e-3 +random_walk_standard_deviation_c_rad_s(0) = 1e-3 +random_walk_standard_deviation_c_rad_s(1) = 1e-3 +random_walk_standard_deviation_c_rad_s(2) = 1e-3 // Range [rad/s] -Range_to_const = 5.0 // smaller than Range_to_zero -Range_to_zero = 10.0 +range_to_constant_rad_s = 5.0 // smaller than Range_to_zero +range_to_zero_rad_s = 10.0 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W +minimum_voltage_V = 3.3 // V +assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index e11dbb143..16cd00225 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -6,6 +6,8 @@ #include +#include "../Abstract/InitializeSensorBase.hpp" + Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); char GSection[30] = "GYRO"; @@ -16,34 +18,9 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, if (prescaler <= 1) prescaler = 1; // SensorBase - // TODO: Use InitializeSensorBase - Vector sf_vec; - gyro_conf.ReadVector(GSection, "ScaleFactor", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kGyroDim; i++) { - for (size_t j = 0; j < kGyroDim; j++) { - scale_factor[i][j] = sf_vec[i * kGyroDim + j]; - } - } - double range_to_const = gyro_conf.ReadDouble(GSection, "Range_to_const"); - Vector range_to_const_c{range_to_const}; - double range_to_zero = gyro_conf.ReadDouble(GSection, "Range_to_zero"); - Vector range_to_zero_c{range_to_zero}; - - Vector bias_c; - gyro_conf.ReadVector(GSection, "Bias_c", bias_c); - - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - gyro_conf.ReadVector(GSection, "rw_stddev_c", rw_stddev_c); - Vector rw_limit_c; - gyro_conf.ReadVector(GSection, "rw_limit_c", rw_limit_c); - Vector nr_stddev_c; - gyro_conf.ReadVector(GSection, "nr_stddev_c", nr_stddev_c); - - SensorBase gyro_sb(scale_factor, range_to_const_c, range_to_zero_c, bias_c, nr_stddev_c, rw_stepwidth, rw_stddev_c, rw_limit_c); + SensorBase<3> sensor_base = ReadSensorBaseInformation<3>(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); - Gyro gyro(prescaler, clock_gen, gyro_sb, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } @@ -54,44 +31,19 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c char GSection[30] = "GYRO"; Quaternion q_b2c; - gyro_conf.ReadQuaternion(GSection, "q_b2c", q_b2c); + gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; // SensorBase - // TODO: Use InitializeSensorBase - Vector sf_vec; - gyro_conf.ReadVector(GSection, "ScaleFactor", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kGyroDim; i++) { - for (size_t j = 0; j < kGyroDim; j++) { - scale_factor[i][j] = sf_vec[i * kGyroDim + j]; - } - } - double range_to_const = gyro_conf.ReadDouble(GSection, "Range_to_const"); - Vector range_to_const_c{range_to_const}; - double range_to_zero = gyro_conf.ReadDouble(GSection, "Range_to_zero"); - Vector range_to_zero_c{range_to_zero}; - - Vector bias_c; - gyro_conf.ReadVector(GSection, "Bias_c", bias_c); - - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - gyro_conf.ReadVector(GSection, "rw_stddev_c", rw_stddev_c); - Vector rw_limit_c; - gyro_conf.ReadVector(GSection, "rw_limit_c", rw_limit_c); - Vector nr_stddev_c; - gyro_conf.ReadVector(GSection, "nr_stddev_c", nr_stddev_c); - - SensorBase gyro_sb(scale_factor, range_to_const_c, range_to_zero_c, bias_c, nr_stddev_c, rw_stepwidth, rw_stddev_c, rw_limit_c); + SensorBase<3> sensor_base = ReadSensorBaseInformation<3>(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); // PowerPort - double minimum_voltage = gyro_conf.ReadDouble(GSection, "minimum_voltage"); + double minimum_voltage = gyro_conf.ReadDouble(GSection, "minimum_voltage_V"); power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = gyro_conf.ReadDouble(GSection, "assumed_power_consumption"); + double assumed_power_consumption = gyro_conf.ReadDouble(GSection, "assumed_power_consumption_W"); power_port->SetAssumedPowerConsumption(assumed_power_consumption); - Gyro gyro(prescaler, clock_gen, power_port, gyro_sb, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } diff --git a/src/Component/Abstract/InitializeSensorBase.hpp b/src/Component/Abstract/InitializeSensorBase.hpp index 98ecd9137..91dddc6e6 100644 --- a/src/Component/Abstract/InitializeSensorBase.hpp +++ b/src/Component/Abstract/InitializeSensorBase.hpp @@ -12,9 +12,11 @@ * @brief Read information from initialize file for SensorBase class * @note It is recommended to use this function for all sensors inherits the SensorBase class * @param [in] file_name: Path to the initialize file - * @param [in] step_width_s: Step width of component updata [sec] + * @param [in] step_width_s: Step width of component update [sec] + * @param [in] component_name: Component name + * @param [in] unit: Unit of the sensor */ template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s); +SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit = ""); #include "InitializeSensorBase_tfs.hpp" diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index 6abed329f..bc53af13d 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -7,12 +7,12 @@ #include "Interface/InitInput/IniAccess.h" template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s) { +SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit) { IniAccess ini_file(file_name); - char section[30] = "SensorBase"; + std::string section = "SensorBase" + component_name; libra::Vector scale_factor_vector; - ini_file.ReadVector(section, "scale_factor_c", scale_factor_vector); + ini_file.ReadVector(section.c_str(), "scale_factor_c", scale_factor_vector); libra::Matrix scale_factor_c; for (size_t i = 0; i < N; i++) { for (size_t j = 0; j < N; j++) { @@ -20,18 +20,26 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl } } + std::string key_name; libra::Vector constant_bias_c; - ini_file.ReadVector(section, "constant_bias_c", constant_bias_c); + key_name = "constant_bias_c_" + unit; + ini_file.ReadVector(section.c_str(), key_name.c_str(), constant_bias_c); libra::Vector normal_random_standard_deviation_c; - ini_file.ReadVector(section, "normal_random_standard_deviation_c", normal_random_standard_deviation_c); + key_name = "normal_random_standard_deviation_c_" + unit; + ini_file.ReadVector(section.c_str(), key_name.c_str(), normal_random_standard_deviation_c); libra::Vector random_walk_standard_deviation_c; - ini_file.ReadVector(section, "random_walk_standard_deviation_c", random_walk_standard_deviation_c); + key_name = "random_walk_standard_deviation_c_" + unit; + ini_file.ReadVector(section.c_str(), key_name.c_str(), random_walk_standard_deviation_c); libra::Vector random_walk_limit_c; - ini_file.ReadVector(section, "random_walk_limit_c", random_walk_limit_c); + key_name = "random_walk_limit_c_" + unit; + ini_file.ReadVector(section.c_str(), key_name.c_str(), random_walk_limit_c); - double range_to_const = ini_file.ReadDouble(section, "range_to_const"); + key_name = "range_to_constant_" + unit; + double range_to_const = ini_file.ReadDouble(section.c_str(), key_name.c_str()); libra::Vector range_to_const_c{range_to_const}; - double range_to_zero = ini_file.ReadDouble(section, "range_to_zero"); + + key_name = "range_to_zero_" + unit; + double range_to_zero = ini_file.ReadDouble(section.c_str(), key_name.c_str()); libra::Vector range_to_zero_c{range_to_zero}; SensorBase sensor_base(scale_factor_c, range_to_const_c, range_to_zero_c, constant_bias_c, normal_random_standard_deviation_c, step_width_s, From 2a8e60ee52eb006977f78280ed7c0b63ddaf0746 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 14:49:33 +0100 Subject: [PATCH 0081/1086] fix small --- data/sample/initialize_files/components/magnetometer.ini | 8 ++++---- src/Component/AOCS/InitGyro.cpp | 2 +- src/Component/AOCS/InitMagSensor.cpp | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/data/sample/initialize_files/components/magnetometer.ini b/data/sample/initialize_files/components/magnetometer.ini index 4e0fd7123..c9e5aa582 100644 --- a/data/sample/initialize_files/components/magnetometer.ini +++ b/data/sample/initialize_files/components/magnetometer.ini @@ -2,10 +2,10 @@ prescaler = 10 //Quaternion from body frame to component frame -q_b2c(0) = 0.0 -q_b2c(1) = 0.0 -q_b2c(2) = 0.0 -q_b2c(3) = 1.0 +quaternion_b2c(0) = 0.0 +quaternion_b2c(1) = 0.0 +quaternion_b2c(2) = 0.0 +quaternion_b2c(3) = 1.0 // Sensor Base // Scale Factor Matrix (3×3) diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 16cd00225..c076b20d0 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -13,7 +13,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, char GSection[30] = "GYRO"; Quaternion q_b2c; - gyro_conf.ReadQuaternion(GSection, "q_b2c", q_b2c); + gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index 4092f8ebf..f44be7c15 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -14,7 +14,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str if (prescaler <= 1) prescaler = 1; Quaternion q_b2c; - magsensor_conf.ReadQuaternion(MSSection, "q_b2c", q_b2c); + magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase // TODO: Use InitializeSensorBase @@ -56,7 +56,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se if (prescaler <= 1) prescaler = 1; Quaternion q_b2c; - magsensor_conf.ReadQuaternion(MSSection, "q_b2c", q_b2c); + magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase // TODO: Use InitializeSensorBase From d2292d19ce570ce5c9189b2a8cd195d2aa7e20a0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 14:59:43 +0100 Subject: [PATCH 0082/1086] Fix initialize file for magnetometer --- .../components/magnetometer.ini | 53 ++++++++-------- src/Component/AOCS/InitGyro.cpp | 4 +- src/Component/AOCS/InitMagSensor.cpp | 61 +++---------------- .../SampleSpacecraft/SampleComponents.cpp | 2 +- 4 files changed, 37 insertions(+), 83 deletions(-) diff --git a/data/sample/initialize_files/components/magnetometer.ini b/data/sample/initialize_files/components/magnetometer.ini index c9e5aa582..d309feaac 100644 --- a/data/sample/initialize_files/components/magnetometer.ini +++ b/data/sample/initialize_files/components/magnetometer.ini @@ -7,43 +7,44 @@ quaternion_b2c(1) = 0.0 quaternion_b2c(2) = 0.0 quaternion_b2c(3) = 1.0 +[SensorBaseMagnetometer] // Sensor Base // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), -ScaleFactor(0) = 1.0 -ScaleFactor(1) = 0.0 -ScaleFactor(2) = 0.0 -ScaleFactor(3) = 0.0 -ScaleFactor(4) = 1.0 -ScaleFactor(5) = 0.0 -ScaleFactor(6) = 0.0 -ScaleFactor(7) = 0.0 -ScaleFactor(8) = 1.0 +scale_factor_c(0) = 1.0 +scale_factor_c(1) = 0.0 +scale_factor_c(2) = 0.0 +scale_factor_c(3) = 0.0 +scale_factor_c(4) = 1.0 +scale_factor_c(5) = 0.0 +scale_factor_c(6) = 0.0 +scale_factor_c(7) = 0.0 +scale_factor_c(8) = 1.0 // Constant bias noise at component frame [nT] -Bias_c(0) = 10.0 -Bias_c(1) = 10.0 -Bias_c(2) = 10.0 +constant_bias_c_nT(0) = 10.0 +constant_bias_c_nT(1) = 10.0 +constant_bias_c_nT(2) = 10.0 // Standard deviation for random walk noise[nT] -rw_stddev_c(0) = 0.0 -rw_stddev_c(1) = 0.0 -rw_stddev_c(2) = 0.0 +random_walk_standard_deviation_c_nT(0) = 0.0 +random_walk_standard_deviation_c_nT(1) = 0.0 +random_walk_standard_deviation_c_nT(2) = 0.0 // Limit of random walk noise[nT] -rw_limit_c(0) = 0.0 -rw_limit_c(1) = 0.0 -rw_limit_c(2) = 0.0 +random_walk_limit_c_nT(0) = 0.0 +random_walk_limit_c_nT(1) = 0.0 +random_walk_limit_c_nT(2) = 0.0 // Standard deviation of normal random noise[nT] -nr_stddev_c(0) = 10.0 -nr_stddev_c(1) = 10.0 -nr_stddev_c(2) = 10.0 +normal_random_standard_deviation_c_nT(0) = 10.0 +normal_random_standard_deviation_c_nT(1) = 10.0 +normal_random_standard_deviation_c_nT(2) = 10.0 -//Range [nT]. -Range_to_const = 1.0e6 // smaller than Range_to_zero -Range_to_zero = 1.5e6 +// Range [nT] +range_to_constant_nT = 1.0e6 // smaller than Range_to_zero +range_to_zero_nT = 1.5e6 // Power Port -minimum_voltage = 3.3 // V -assumed_power_consumption = 1.0 //W \ No newline at end of file +minimum_voltage_V = 3.3 // V +assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index c076b20d0..328a97f33 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -18,7 +18,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, if (prescaler <= 1) prescaler = 1; // SensorBase - SensorBase<3> sensor_base = ReadSensorBaseInformation<3>(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); Gyro gyro(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, dynamics); @@ -36,7 +36,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c if (prescaler <= 1) prescaler = 1; // SensorBase - SensorBase<3> sensor_base = ReadSensorBaseInformation<3>(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); // PowerPort double minimum_voltage = gyro_conf.ReadDouble(GSection, "minimum_voltage_V"); diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index f44be7c15..0b87ac0ac 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -4,6 +4,7 @@ */ #include "InitMagSensor.hpp" +#include "../Abstract/InitializeSensorBase.hpp" #include "Interface/InitInput/IniAccess.h" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { @@ -17,33 +18,9 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase - // TODO: Use InitializeSensorBase - Vector sf_vec; - magsensor_conf.ReadVector(MSSection, "ScaleFactor", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kMagDim; i++) { - for (size_t j = 0; j < kMagDim; j++) { - scale_factor[i][j] = sf_vec[i * kMagDim + j]; - } - } - double range_to_const = magsensor_conf.ReadDouble(MSSection, "Range_to_const"); - Vector range_to_const_c{range_to_const}; - double range_to_zero = magsensor_conf.ReadDouble(MSSection, "Range_to_zero"); - Vector range_to_zero_c{range_to_zero}; + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Magnetometer", "nT"); - Vector bias_c; - magsensor_conf.ReadVector(MSSection, "Bias_c", bias_c); - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - magsensor_conf.ReadVector(MSSection, "rw_stddev_c", rw_stddev_c); - Vector rw_limit_c; - magsensor_conf.ReadVector(MSSection, "rw_limit_c", rw_limit_c); - Vector nr_stddev_c; - magsensor_conf.ReadVector(MSSection, "nr_stddev_c", nr_stddev_c); - - SensorBase mag_sb(scale_factor, range_to_const_c, range_to_zero_c, bias_c, nr_stddev_c, rw_stepwidth, rw_stddev_c, rw_limit_c); - - MagSensor magsensor(prescaler, clock_gen, mag_sb, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, magnet); return magsensor; } @@ -59,38 +36,14 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase - // TODO: Use InitializeSensorBase - Vector sf_vec; - magsensor_conf.ReadVector(MSSection, "ScaleFactor", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kMagDim; i++) { - for (size_t j = 0; j < kMagDim; j++) { - scale_factor[i][j] = sf_vec[i * kMagDim + j]; - } - } - double range_to_const = magsensor_conf.ReadDouble(MSSection, "Range_to_const"); - Vector range_to_const_c{range_to_const}; - double range_to_zero = magsensor_conf.ReadDouble(MSSection, "Range_to_zero"); - Vector range_to_zero_c{range_to_zero}; - - Vector bias_c; - magsensor_conf.ReadVector(MSSection, "Bias_c", bias_c); - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - magsensor_conf.ReadVector(MSSection, "rw_stddev_c", rw_stddev_c); - Vector rw_limit_c; - magsensor_conf.ReadVector(MSSection, "rw_limit_c", rw_limit_c); - Vector nr_stddev_c; - magsensor_conf.ReadVector(MSSection, "nr_stddev_c", nr_stddev_c); - - SensorBase mag_sb(scale_factor, range_to_const_c, range_to_zero_c, bias_c, nr_stddev_c, rw_stepwidth, rw_stddev_c, rw_limit_c); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Magnetometer", "nT"); // PowerPort - double minimum_voltage = magsensor_conf.ReadDouble(MSSection, "minimum_voltage"); + double minimum_voltage = magsensor_conf.ReadDouble(MSSection, "minimum_voltage_V"); power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = magsensor_conf.ReadDouble(MSSection, "assumed_power_consumption"); + double assumed_power_consumption = magsensor_conf.ReadDouble(MSSection, "assumed_power_consumption_W"); power_port->AddAssumedPowerConsumption(assumed_power_consumption); - MagSensor magsensor(prescaler, clock_gen, power_port, mag_sb, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, magnet); return magsensor; } diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp index 05c75365b..5250e2fc5 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp @@ -30,7 +30,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), dynamics_)); // MagSensor - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "mag_sensor_file"); + ini_path = iniAccess.ReadString("COMPONENTS_FILE", "magetometer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_sensor_ = new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); From 6322d0dd492071ce4ddfef0b6ac57839cc2ec3f9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 15:06:07 +0100 Subject: [PATCH 0083/1086] Fix format --- src/Component/Abstract/InitializeSensorBase.hpp | 3 ++- src/Component/Abstract/InitializeSensorBase_tfs.hpp | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/Component/Abstract/InitializeSensorBase.hpp b/src/Component/Abstract/InitializeSensorBase.hpp index 91dddc6e6..5bd3b5132 100644 --- a/src/Component/Abstract/InitializeSensorBase.hpp +++ b/src/Component/Abstract/InitializeSensorBase.hpp @@ -17,6 +17,7 @@ * @param [in] unit: Unit of the sensor */ template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit = ""); +SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, + const std::string unit = ""); #include "InitializeSensorBase_tfs.hpp" diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index bc53af13d..72e6bff29 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -7,7 +7,8 @@ #include "Interface/InitInput/IniAccess.h" template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit) { +SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, + const std::string unit) { IniAccess ini_file(file_name); std::string section = "SensorBase" + component_name; From fdbea26411b4c866052f602675a2a01e56bde7b7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 15:22:13 +0100 Subject: [PATCH 0084/1086] Move gen_graph --- data/{SampleSat => sample}/gen_graph.sh | 0 data/{SampleSat => sample}/graph.toml | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename data/{SampleSat => sample}/gen_graph.sh (100%) rename data/{SampleSat => sample}/graph.toml (100%) diff --git a/data/SampleSat/gen_graph.sh b/data/sample/gen_graph.sh similarity index 100% rename from data/SampleSat/gen_graph.sh rename to data/sample/gen_graph.sh diff --git a/data/SampleSat/graph.toml b/data/sample/graph.toml similarity index 100% rename from data/SampleSat/graph.toml rename to data/sample/graph.toml From 7740625e1c117e40564aa392053bd7c3f9d66cb5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 15:32:57 +0100 Subject: [PATCH 0085/1086] Delete SampleSat --- data/SampleSat/logs/.gitkeep | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 data/SampleSat/logs/.gitkeep diff --git a/data/SampleSat/logs/.gitkeep b/data/SampleSat/logs/.gitkeep deleted file mode 100644 index e69de29bb..000000000 From 6ac2bc5de148ee06aada715c7fb25ac88d530f6c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:26:26 +0100 Subject: [PATCH 0086/1086] Rename temporary to change to lower case --- src/Component/{Examples => examples_temp}/ChangeStructure.cpp | 0 src/Component/{Examples => examples_temp}/ChangeStructure.hpp | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/Component/{Examples => examples_temp}/ChangeStructure.cpp (100%) rename src/Component/{Examples => examples_temp}/ChangeStructure.hpp (100%) diff --git a/src/Component/Examples/ChangeStructure.cpp b/src/Component/examples_temp/ChangeStructure.cpp similarity index 100% rename from src/Component/Examples/ChangeStructure.cpp rename to src/Component/examples_temp/ChangeStructure.cpp diff --git a/src/Component/Examples/ChangeStructure.hpp b/src/Component/examples_temp/ChangeStructure.hpp similarity index 100% rename from src/Component/Examples/ChangeStructure.hpp rename to src/Component/examples_temp/ChangeStructure.hpp From 5466f6b176decf5319f5f160547ca5f965f1002f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:26:51 +0100 Subject: [PATCH 0087/1086] Rename example directory --- src/Component/{examples_temp => examples}/ChangeStructure.cpp | 0 src/Component/{examples_temp => examples}/ChangeStructure.hpp | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/Component/{examples_temp => examples}/ChangeStructure.cpp (100%) rename src/Component/{examples_temp => examples}/ChangeStructure.hpp (100%) diff --git a/src/Component/examples_temp/ChangeStructure.cpp b/src/Component/examples/ChangeStructure.cpp similarity index 100% rename from src/Component/examples_temp/ChangeStructure.cpp rename to src/Component/examples/ChangeStructure.cpp diff --git a/src/Component/examples_temp/ChangeStructure.hpp b/src/Component/examples/ChangeStructure.hpp similarity index 100% rename from src/Component/examples_temp/ChangeStructure.hpp rename to src/Component/examples/ChangeStructure.hpp From 78fe01342a2c0f8ca2348b20d47bfd3fb462576f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:32:32 +0100 Subject: [PATCH 0088/1086] Rename EXP --- .../EXP.cpp => examples/serial_communication_with_obc.cpp} | 0 .../EXP.h => examples/serial_communication_with_obc.hpp} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename src/Component/{Abstract/EXP.cpp => examples/serial_communication_with_obc.cpp} (100%) rename src/Component/{Abstract/EXP.h => examples/serial_communication_with_obc.hpp} (100%) diff --git a/src/Component/Abstract/EXP.cpp b/src/Component/examples/serial_communication_with_obc.cpp similarity index 100% rename from src/Component/Abstract/EXP.cpp rename to src/Component/examples/serial_communication_with_obc.cpp diff --git a/src/Component/Abstract/EXP.h b/src/Component/examples/serial_communication_with_obc.hpp similarity index 100% rename from src/Component/Abstract/EXP.h rename to src/Component/examples/serial_communication_with_obc.hpp From c1905ddde5391faca88a590517a7a39f02a9e680 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:36:31 +0100 Subject: [PATCH 0089/1086] Fix example directory name --- src/Component/CMakeLists.txt | 4 ++-- src/Component/examples/serial_communication_with_obc.cpp | 2 +- src/Component/examples/serial_communication_with_obc.hpp | 6 +++--- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 0aa8932d2..f9a27dc2d 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -7,7 +7,6 @@ add_library(${PROJECT_NAME} STATIC Abstract/I2cControllerCommunicationBase.cpp Abstract/ObcI2cTargetCommunicationBase.cpp Abstract/ObcGpioBase.cpp - Abstract/EXP.cpp Abstract/ExpHils.cpp Abstract/ExpHilsI2cController.cpp Abstract/ExpHilsI2cTarget.cpp @@ -38,7 +37,8 @@ add_library(${PROJECT_NAME} STATIC CommGS/GScalculator.cpp CommGS/InitGsCalculator.cpp - Examples/ChangeStructure.cpp + examples/ChangeStructure.cpp + examples/serial_communication_with_obc.cpp IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/examples/serial_communication_with_obc.cpp b/src/Component/examples/serial_communication_with_obc.cpp index 153692f81..9bb31f1ad 100644 --- a/src/Component/examples/serial_communication_with_obc.cpp +++ b/src/Component/examples/serial_communication_with_obc.cpp @@ -3,7 +3,7 @@ * @brief Example of component emulation with communication between OBC Flight software */ -#include "EXP.h" +#include "serial_communication_with_obc.hpp" #include diff --git a/src/Component/examples/serial_communication_with_obc.hpp b/src/Component/examples/serial_communication_with_obc.hpp index 601427007..0c9a6a6a1 100644 --- a/src/Component/examples/serial_communication_with_obc.hpp +++ b/src/Component/examples/serial_communication_with_obc.hpp @@ -6,9 +6,9 @@ #pragma once #include -#include "ComponentBase.h" -#include "IGPIOCompo.h" -#include "ObcCommunicationBase.h" +#include "../Abstract/ComponentBase.h" +#include "../Abstract/IGPIOCompo.h" +#include "../Abstract/ObcCommunicationBase.h" /** * @class EXP diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 330c0c98f..b58a1e641 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include #include From 445a96598edd478f4e1a29f665184e4751ee0a0c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:39:52 +0100 Subject: [PATCH 0090/1086] Rename EXP class --- .../serial_communication_with_obc.cpp | 24 ++++++++++++------- .../serial_communication_with_obc.hpp | 20 ++++++++-------- 2 files changed, 25 insertions(+), 19 deletions(-) diff --git a/src/Component/examples/serial_communication_with_obc.cpp b/src/Component/examples/serial_communication_with_obc.cpp index 9bb31f1ad..8bbcd7a12 100644 --- a/src/Component/examples/serial_communication_with_obc.cpp +++ b/src/Component/examples/serial_communication_with_obc.cpp @@ -1,5 +1,5 @@ /** - * @file EXP.cpp + * @file serial_communication_with_obc.cpp * @brief Example of component emulation with communication between OBC Flight software */ @@ -7,21 +7,25 @@ #include -EXP::EXP(ClockGenerator* clock_gen, int port_id, OBC* obc) : ComponentBase(1000, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } -EXP::EXP(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) : ComponentBase(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { +SerialCommunicationWithObc::SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) + : ComponentBase(1000, clock_gen), ObcCommunicationBase(port_id, obc) { + Initialize(); +} +SerialCommunicationWithObc::SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) + : ComponentBase(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } -int EXP::Initialize() { +int SerialCommunicationWithObc::Initialize() { for (int i = 0; i < MAX_MEMORY_LEN; i++) { memory.push_back(0); } return 0; } -EXP::~EXP() {} +SerialCommunicationWithObc::~SerialCommunicationWithObc() {} -int EXP::ParseCommand(const int cmd_size) { +int SerialCommunicationWithObc::ParseCommand(const int cmd_size) { if (cmd_size < 4) { return -1; } @@ -33,17 +37,19 @@ int EXP::ParseCommand(const int cmd_size) { memory[MAX_MEMORY_LEN - 1] = '\n'; return 0; } -int EXP::GenerateTelemetry() { +int SerialCommunicationWithObc::GenerateTelemetry() { for (int i = 0; i < MAX_MEMORY_LEN; i++) { tx_buff[i] = (unsigned char)memory[i]; } tx_buffer_.assign(std::begin(tx_buff), std::end(tx_buff)); return sizeof(tx_buff); } -void EXP::MainRoutine(int count) { +void SerialCommunicationWithObc::MainRoutine(int count) { UNUSED(count); ReceiveCommand(0, 5); SendTelemetry(0); } -void EXP::GPIOStateChanged(int port_id, bool isPosedge) { printf("interrupted. portid = %d, isPosedge = %d./n", port_id, isPosedge); } +void SerialCommunicationWithObc::GPIOStateChanged(int port_id, bool isPosedge) { + printf("interrupted. portid = %d, isPosedge = %d./n", port_id, isPosedge); +} diff --git a/src/Component/examples/serial_communication_with_obc.hpp b/src/Component/examples/serial_communication_with_obc.hpp index 0c9a6a6a1..caf6e6ef1 100644 --- a/src/Component/examples/serial_communication_with_obc.hpp +++ b/src/Component/examples/serial_communication_with_obc.hpp @@ -1,5 +1,5 @@ /** - * @file EXP.h + * @file serial_communication_with_obc.hpp * @brief Example of component emulation with communication between OBC Flight software */ @@ -11,7 +11,7 @@ #include "../Abstract/ObcCommunicationBase.h" /** - * @class EXP + * @class SerialCommunicationWithObc * @brief Example of component emulation with communication between OBC Flight software * @details Command to EXP is 5 bytes. * - The first 3 bytes: "SET" @@ -23,31 +23,31 @@ * - The last byte: "\n" * - The telemetry is automatically generated */ -class EXP : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo { +class SerialCommunicationWithObc : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo { public: /** - * @fn EXP + * @fn SerialCommunicationWithObc * @brief Constructor without prescaler * @note The prescaler is set as 1000 * @param [in] clock_gen: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] obc: The communication target OBC */ - EXP(ClockGenerator* clock_gen, int port_id, OBC* obc); + SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc); /** - * @fn EXP + * @fn SerialCommunicationWithObc * @brief Constructor * @param [in] clock_gen: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] prescaler: Frequency scale factor for update * @param [in] obc: The communication target OBC */ - EXP(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc); + SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc); /** - * @fn ~EXP + * @fn ~SerialCommunicationWithObc * @brief Destructor */ - ~EXP(); + ~SerialCommunicationWithObc(); protected: // Override functions for ComponentBase @@ -88,4 +88,4 @@ class EXP : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo * @brief Initialize function */ int Initialize(); -}; \ No newline at end of file +}; From 44f2b2094b0abec5bbfeff02dc1679152c174b72 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:44:56 +0100 Subject: [PATCH 0091/1086] Add example_ --- src/Component/CMakeLists.txt | 2 +- ...example_serial_communication_with_obc.cpp} | 20 +++++++++---------- ...example_serial_communication_with_obc.hpp} | 16 +++++++-------- 3 files changed, 19 insertions(+), 19 deletions(-) rename src/Component/examples/{serial_communication_with_obc.cpp => example_serial_communication_with_obc.cpp} (55%) rename src/Component/examples/{serial_communication_with_obc.hpp => example_serial_communication_with_obc.hpp} (82%) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index f9a27dc2d..11324d045 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -38,7 +38,7 @@ add_library(${PROJECT_NAME} STATIC CommGS/InitGsCalculator.cpp examples/ChangeStructure.cpp - examples/serial_communication_with_obc.cpp + examples/example_serial_communication_with_obc.cpp IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/examples/serial_communication_with_obc.cpp b/src/Component/examples/example_serial_communication_with_obc.cpp similarity index 55% rename from src/Component/examples/serial_communication_with_obc.cpp rename to src/Component/examples/example_serial_communication_with_obc.cpp index 8bbcd7a12..c7adbd473 100644 --- a/src/Component/examples/serial_communication_with_obc.cpp +++ b/src/Component/examples/example_serial_communication_with_obc.cpp @@ -1,31 +1,31 @@ /** - * @file serial_communication_with_obc.cpp + * @file example_serial_communication_with_obc.cpp * @brief Example of component emulation with communication between OBC Flight software */ -#include "serial_communication_with_obc.hpp" +#include "example_serial_communication_with_obc.hpp" #include -SerialCommunicationWithObc::SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) : ComponentBase(1000, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } -SerialCommunicationWithObc::SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) : ComponentBase(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } -int SerialCommunicationWithObc::Initialize() { +int ExampleSerialCommunicationWithObc::Initialize() { for (int i = 0; i < MAX_MEMORY_LEN; i++) { memory.push_back(0); } return 0; } -SerialCommunicationWithObc::~SerialCommunicationWithObc() {} +ExampleSerialCommunicationWithObc::~ExampleSerialCommunicationWithObc() {} -int SerialCommunicationWithObc::ParseCommand(const int cmd_size) { +int ExampleSerialCommunicationWithObc::ParseCommand(const int cmd_size) { if (cmd_size < 4) { return -1; } @@ -37,19 +37,19 @@ int SerialCommunicationWithObc::ParseCommand(const int cmd_size) { memory[MAX_MEMORY_LEN - 1] = '\n'; return 0; } -int SerialCommunicationWithObc::GenerateTelemetry() { +int ExampleSerialCommunicationWithObc::GenerateTelemetry() { for (int i = 0; i < MAX_MEMORY_LEN; i++) { tx_buff[i] = (unsigned char)memory[i]; } tx_buffer_.assign(std::begin(tx_buff), std::end(tx_buff)); return sizeof(tx_buff); } -void SerialCommunicationWithObc::MainRoutine(int count) { +void ExampleSerialCommunicationWithObc::MainRoutine(int count) { UNUSED(count); ReceiveCommand(0, 5); SendTelemetry(0); } -void SerialCommunicationWithObc::GPIOStateChanged(int port_id, bool isPosedge) { +void ExampleSerialCommunicationWithObc::GPIOStateChanged(int port_id, bool isPosedge) { printf("interrupted. portid = %d, isPosedge = %d./n", port_id, isPosedge); } diff --git a/src/Component/examples/serial_communication_with_obc.hpp b/src/Component/examples/example_serial_communication_with_obc.hpp similarity index 82% rename from src/Component/examples/serial_communication_with_obc.hpp rename to src/Component/examples/example_serial_communication_with_obc.hpp index caf6e6ef1..d1e5efbd4 100644 --- a/src/Component/examples/serial_communication_with_obc.hpp +++ b/src/Component/examples/example_serial_communication_with_obc.hpp @@ -1,5 +1,5 @@ /** - * @file serial_communication_with_obc.hpp + * @file example_serial_communication_with_obc.hpp * @brief Example of component emulation with communication between OBC Flight software */ @@ -11,7 +11,7 @@ #include "../Abstract/ObcCommunicationBase.h" /** - * @class SerialCommunicationWithObc + * @class ExampleSerialCommunicationWithObc * @brief Example of component emulation with communication between OBC Flight software * @details Command to EXP is 5 bytes. * - The first 3 bytes: "SET" @@ -23,31 +23,31 @@ * - The last byte: "\n" * - The telemetry is automatically generated */ -class SerialCommunicationWithObc : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo { +class ExampleSerialCommunicationWithObc : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo { public: /** - * @fn SerialCommunicationWithObc + * @fn ExampleSerialCommunicationWithObc * @brief Constructor without prescaler * @note The prescaler is set as 1000 * @param [in] clock_gen: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] obc: The communication target OBC */ - SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc); /** - * @fn SerialCommunicationWithObc + * @fn ExampleSerialCommunicationWithObc * @brief Constructor * @param [in] clock_gen: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] prescaler: Frequency scale factor for update * @param [in] obc: The communication target OBC */ - SerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc); /** * @fn ~SerialCommunicationWithObc * @brief Destructor */ - ~SerialCommunicationWithObc(); + ~ExampleSerialCommunicationWithObc(); protected: // Override functions for ComponentBase From 34910665d71c7fb191d0a2a7e5e7a9e7b1904e8e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:49:46 +0100 Subject: [PATCH 0092/1086] Rename ExpHils --- src/Component/CMakeLists.txt | 2 +- .../example_serial_communication_for_hils.cpp} | 4 ++-- .../example_serial_communication_for_hils.hpp} | 6 +++--- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) rename src/Component/{Abstract/ExpHils.cpp => examples/example_serial_communication_for_hils.cpp} (94%) rename src/Component/{Abstract/ExpHils.h => examples/example_serial_communication_for_hils.hpp} (94%) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 11324d045..40e2de3c1 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -7,7 +7,6 @@ add_library(${PROJECT_NAME} STATIC Abstract/I2cControllerCommunicationBase.cpp Abstract/ObcI2cTargetCommunicationBase.cpp Abstract/ObcGpioBase.cpp - Abstract/ExpHils.cpp Abstract/ExpHilsI2cController.cpp Abstract/ExpHilsI2cTarget.cpp @@ -39,6 +38,7 @@ add_library(${PROJECT_NAME} STATIC examples/ChangeStructure.cpp examples/example_serial_communication_with_obc.cpp + examples/example_serial_communication_for_hils.cpp IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/Abstract/ExpHils.cpp b/src/Component/examples/example_serial_communication_for_hils.cpp similarity index 94% rename from src/Component/Abstract/ExpHils.cpp rename to src/Component/examples/example_serial_communication_for_hils.cpp index cce161fdb..34b5ba947 100644 --- a/src/Component/Abstract/ExpHils.cpp +++ b/src/Component/examples/example_serial_communication_for_hils.cpp @@ -1,8 +1,8 @@ /** - * @file ExpHils.cpp + * @file example_serial_communication_for_hils.cpp * @brief Example of component emulation for UART communication in HILS environment */ -#include "ExpHils.h" +#include "example_serial_communication_for_hils.hpp" #include diff --git a/src/Component/Abstract/ExpHils.h b/src/Component/examples/example_serial_communication_for_hils.hpp similarity index 94% rename from src/Component/Abstract/ExpHils.h rename to src/Component/examples/example_serial_communication_for_hils.hpp index 3889e4ef3..5fb63dfbc 100644 --- a/src/Component/Abstract/ExpHils.h +++ b/src/Component/examples/example_serial_communication_for_hils.hpp @@ -1,12 +1,12 @@ /** - * @file ExpHils.h + * @file example_serial_communication_for_hils.hpp * @brief Example of component emulation for UART communication in HILS environment */ #pragma once #include -#include "ComponentBase.h" -#include "ObcCommunicationBase.h" +#include "../Abstract/ComponentBase.h" +#include "../Abstract/ObcCommunicationBase.h" /** * @class ExpHils diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index b58a1e641..58735ba99 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -4,7 +4,6 @@ */ #pragma once -#include #include #include #include @@ -21,9 +20,10 @@ #include #include #include -#include #include #include +#include +#include #include #include "../InstalledComponents.hpp" From 86fa4284901c5b40c3fdd66f5ea507af3695addf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:53:36 +0100 Subject: [PATCH 0093/1086] Rename ExpHils class --- .../example_serial_communication_for_hils.cpp | 13 +++++++------ .../example_serial_communication_for_hils.hpp | 14 +++++++------- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 4 ++-- 3 files changed, 16 insertions(+), 15 deletions(-) diff --git a/src/Component/examples/example_serial_communication_for_hils.cpp b/src/Component/examples/example_serial_communication_for_hils.cpp index 34b5ba947..644008aa2 100644 --- a/src/Component/examples/example_serial_communication_for_hils.cpp +++ b/src/Component/examples/example_serial_communication_for_hils.cpp @@ -6,13 +6,14 @@ #include -ExpHils::ExpHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, - HilsPortManager* hils_port_manager, const int mode_id) +ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, + const unsigned int hils_port_id, const unsigned int baud_rate, + HilsPortManager* hils_port_manager, const int mode_id) : ComponentBase(300, clock_gen), ObcCommunicationBase(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} -ExpHils::~ExpHils() {} +ExampleSerialCommunicationForHils::~ExampleSerialCommunicationForHils() {} -int ExpHils::ParseCommand(const int cmd_size) { +int ExampleSerialCommunicationForHils::ParseCommand(const int cmd_size) { UNUSED(cmd_size); if (mode_id_ == 1) { @@ -28,7 +29,7 @@ int ExpHils::ParseCommand(const int cmd_size) { return 0; } -int ExpHils::GenerateTelemetry() { +int ExampleSerialCommunicationForHils::GenerateTelemetry() { if (mode_id_ == 0) // The sender component sends ABC, BCD, CDE ... { for (int i = 0; i < kMemorySize; i++) { @@ -52,7 +53,7 @@ int ExpHils::GenerateTelemetry() { return 0; } -void ExpHils::MainRoutine(int count) { +void ExampleSerialCommunicationForHils::MainRoutine(int count) { UNUSED(count); ReceiveCommand(0, kMemorySize); diff --git a/src/Component/examples/example_serial_communication_for_hils.hpp b/src/Component/examples/example_serial_communication_for_hils.hpp index 5fb63dfbc..e3c1e5c20 100644 --- a/src/Component/examples/example_serial_communication_for_hils.hpp +++ b/src/Component/examples/example_serial_communication_for_hils.hpp @@ -9,7 +9,7 @@ #include "../Abstract/ObcCommunicationBase.h" /** - * @class ExpHils + * @class ExampleSerialCommunicationForHils * @brief Example of component emulation for communication in HILS environment * @details The sender mode: ExpHils sends out a new massage * - message size is 4 bytes @@ -17,10 +17,10 @@ * - the last byte : \0 * The responder mode: ExpHils returns the message as received */ -class ExpHils : public ComponentBase, public ObcCommunicationBase { +class ExampleSerialCommunicationForHils : public ComponentBase, public ObcCommunicationBase { public: /** - * @fn ExpHils + * @fn ExampleSerialCommunicationForHils * @brief Constructor * @note prescaler is set as 300. * @param [in] clock_gen: Clock generator @@ -31,13 +31,13 @@ class ExpHils : public ComponentBase, public ObcCommunicationBase { * @param [in] hils_port_manager: HILS port manager * @param [in] mode_id: Mode ID to select sender(0) or responder(1) */ - ExpHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, - HilsPortManager* hils_port_manager, const int mode_id); + ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, + const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id); /** - * @fn ~ExpHils + * @fn ~ExampleSerialCommunicationForHils * @brief Destructor */ - ~ExpHils(); + ~ExampleSerialCommunicationForHils(); protected: // Override functions for ComponentBase diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 58735ba99..b4369ef57 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -102,8 +102,8 @@ class SampleComponents : public InstalledComponents { // HILS settings examples /* - ExpHils* exp_hils_uart_responder_; //!< Example of HILS UART responder - ExpHils* exp_hils_uart_sender_; //!< Example of HILS UART sender + ExampleSerialCommunicationForHils* exp_hils_uart_responder_; //!< Example of HILS UART responder + ExampleSerialCommunicationForHils* exp_hils_uart_sender_; //!< Example of HILS UART sender ExpHilsI2cController* exp_hils_i2c_controller_; //!< Example of HILS I2C controller ExpHilsI2cTarget* exp_hils_i2c_target_; //!< Example of HILS I2C target */ From 8629854b9912c84a3f676c1aa10d3130251a8e14 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 18:58:43 +0100 Subject: [PATCH 0094/1086] Rename ExpHilsI2cController file --- src/Component/CMakeLists.txt | 2 +- .../example_i2c_controller_for_hils.cpp} | 4 ++-- .../example_i2c_controller_for_hils.hpp} | 6 +++--- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) rename src/Component/{Abstract/ExpHilsI2cController.cpp => examples/example_i2c_controller_for_hils.cpp} (95%) rename src/Component/{Abstract/ExpHilsI2cController.h => examples/example_i2c_controller_for_hils.hpp} (94%) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 40e2de3c1..c093489ac 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -7,7 +7,6 @@ add_library(${PROJECT_NAME} STATIC Abstract/I2cControllerCommunicationBase.cpp Abstract/ObcI2cTargetCommunicationBase.cpp Abstract/ObcGpioBase.cpp - Abstract/ExpHilsI2cController.cpp Abstract/ExpHilsI2cTarget.cpp AOCS/Gyro.cpp @@ -39,6 +38,7 @@ add_library(${PROJECT_NAME} STATIC examples/ChangeStructure.cpp examples/example_serial_communication_with_obc.cpp examples/example_serial_communication_for_hils.cpp + examples/example_i2c_controller_for_hils.cpp IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/Abstract/ExpHilsI2cController.cpp b/src/Component/examples/example_i2c_controller_for_hils.cpp similarity index 95% rename from src/Component/Abstract/ExpHilsI2cController.cpp rename to src/Component/examples/example_i2c_controller_for_hils.cpp index 64c2368d5..f9b0d5598 100644 --- a/src/Component/Abstract/ExpHilsI2cController.cpp +++ b/src/Component/examples/example_i2c_controller_for_hils.cpp @@ -1,8 +1,8 @@ /** - * @file ExpHilsI2cController.cpp + * @file example_i2c_controller_for_hils.cpp * @brief Example of component emulation for I2C controller side communication in HILS environment */ -#include "ExpHilsI2cController.h" +#include "example_i2c_controller_for_hils.hpp" ExpHilsI2cController::ExpHilsI2cController(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, diff --git a/src/Component/Abstract/ExpHilsI2cController.h b/src/Component/examples/example_i2c_controller_for_hils.hpp similarity index 94% rename from src/Component/Abstract/ExpHilsI2cController.h rename to src/Component/examples/example_i2c_controller_for_hils.hpp index 4357f2c27..37545e7c5 100644 --- a/src/Component/Abstract/ExpHilsI2cController.h +++ b/src/Component/examples/example_i2c_controller_for_hils.hpp @@ -1,12 +1,12 @@ /** - * @file ExpHilsI2cController.h + * @file example_i2c_controller_for_hils.hpp * @brief Example of component emulation for I2C controller side communication in HILS environment */ #pragma once #include -#include "ComponentBase.h" -#include "I2cControllerCommunicationBase.h" +#include "../Abstract/ComponentBase.h" +#include "../Abstract/I2cControllerCommunicationBase.h" /** * @class ExpHilsI2cController diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index b4369ef57..f54ee9396 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -4,7 +4,6 @@ */ #pragma once -#include #include #include #include @@ -23,6 +22,7 @@ #include #include #include +#include #include #include From 664ecb9db9b8d25c4789969fbd10e3d2405cbff1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:01:31 +0100 Subject: [PATCH 0095/1086] Rename HilsI2cController class --- .../examples/example_i2c_controller_for_hils.cpp | 10 +++++----- .../examples/example_i2c_controller_for_hils.hpp | 12 ++++++------ .../Spacecraft/SampleSpacecraft/SampleComponents.h | 4 +--- 3 files changed, 12 insertions(+), 14 deletions(-) diff --git a/src/Component/examples/example_i2c_controller_for_hils.cpp b/src/Component/examples/example_i2c_controller_for_hils.cpp index f9b0d5598..b86298678 100644 --- a/src/Component/examples/example_i2c_controller_for_hils.cpp +++ b/src/Component/examples/example_i2c_controller_for_hils.cpp @@ -4,14 +4,14 @@ */ #include "example_i2c_controller_for_hils.hpp" -ExpHilsI2cController::ExpHilsI2cController(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, +ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager) : ComponentBase(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buf_size, rx_buf_size, hils_port_manager) {} -ExpHilsI2cController::~ExpHilsI2cController() {} +ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} -void ExpHilsI2cController::MainRoutine(int count) { +void ExampleI2cControllerForHils::MainRoutine(int count) { UNUSED(count); RequestTlm(); @@ -19,7 +19,7 @@ void ExpHilsI2cController::MainRoutine(int count) { return; } -void ExpHilsI2cController::RequestTlm() { +void ExampleI2cControllerForHils::RequestTlm() { const unsigned char kReqTlmCmdSize = 5; unsigned char req_tlm_cmd[kReqTlmCmdSize]; req_tlm_cmd[0] = kCmdHeader_; @@ -33,7 +33,7 @@ void ExpHilsI2cController::RequestTlm() { return; } -void ExpHilsI2cController::Receive() { +void ExampleI2cControllerForHils::Receive() { const unsigned char kTlmSize = 5; const unsigned char kReceiveCmdSize = 4; unsigned char receive_cmd[kReceiveCmdSize]; diff --git a/src/Component/examples/example_i2c_controller_for_hils.hpp b/src/Component/examples/example_i2c_controller_for_hils.hpp index 37545e7c5..e55f6062d 100644 --- a/src/Component/examples/example_i2c_controller_for_hils.hpp +++ b/src/Component/examples/example_i2c_controller_for_hils.hpp @@ -9,16 +9,16 @@ #include "../Abstract/I2cControllerCommunicationBase.h" /** - * @class ExpHilsI2cController + * @class ExampleI2cControllerForHils * @brief Example of component emulation for I2C controller side communication in HILS environment * @details Supposed to be used in connection with the following I2C-USB Controller converter * SC18IM700 Data Sheet: https://www.nxp.com/docs/en/data-sheet/SC18IM700.pdf * telemetry size = 5 bytes(ASCII) */ -class ExpHilsI2cController : public ComponentBase, public I2cControllerCommunicationBase { +class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCommunicationBase { public: /** - * @fn ExpHilsI2cController + * @fn ExampleI2cControllerForHils * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_gen: Clock generator @@ -28,13 +28,13 @@ class ExpHilsI2cController : public ComponentBase, public I2cControllerCommunica * @param [in] rx_buf_size: RX (Target to Controller) buffer size * @param [in] hils_port_manager: HILS port manager */ - ExpHilsI2cController(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, + ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager); /** - * @fn ~ExpHilsI2cController + * @fn ~ExampleI2cControllerForHils * @brief Destructor */ - ~ExpHilsI2cController(); + ~ExampleI2cControllerForHils(); protected: // Override functions for ComponentBase diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index f54ee9396..2b3fdd15b 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -99,12 +99,10 @@ class SampleComponents : public InstalledComponents { // Examples // ChangeStructure* change_structure_; //!< Change structure - - // HILS settings examples /* ExampleSerialCommunicationForHils* exp_hils_uart_responder_; //!< Example of HILS UART responder ExampleSerialCommunicationForHils* exp_hils_uart_sender_; //!< Example of HILS UART sender - ExpHilsI2cController* exp_hils_i2c_controller_; //!< Example of HILS I2C controller + ExampleI2cControllerForHils* exp_hils_i2c_controller_; //!< Example of HILS I2C controller ExpHilsI2cTarget* exp_hils_i2c_target_; //!< Example of HILS I2C target */ From bad7412a9ac74ec18d370efba7a2a642f60f62db Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:05:17 +0100 Subject: [PATCH 0096/1086] Rename ExpHilsI2cTarget file --- src/Component/CMakeLists.txt | 2 +- .../example_i2c_target_for_hils.cpp} | 4 ++-- .../example_i2c_target_for_hils.hpp} | 6 +++--- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) rename src/Component/{Abstract/ExpHilsI2cTarget.cpp => examples/example_i2c_target_for_hils.cpp} (94%) rename src/Component/{Abstract/ExpHilsI2cTarget.h => examples/example_i2c_target_for_hils.hpp} (93%) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index c093489ac..201897812 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -7,7 +7,6 @@ add_library(${PROJECT_NAME} STATIC Abstract/I2cControllerCommunicationBase.cpp Abstract/ObcI2cTargetCommunicationBase.cpp Abstract/ObcGpioBase.cpp - Abstract/ExpHilsI2cTarget.cpp AOCS/Gyro.cpp AOCS/InitGyro.cpp @@ -39,6 +38,7 @@ add_library(${PROJECT_NAME} STATIC examples/example_serial_communication_with_obc.cpp examples/example_serial_communication_for_hils.cpp examples/example_i2c_controller_for_hils.cpp + examples/example_i2c_target_for_hils.cpp IdealComponents/ForceGenerator.cpp IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/Abstract/ExpHilsI2cTarget.cpp b/src/Component/examples/example_i2c_target_for_hils.cpp similarity index 94% rename from src/Component/Abstract/ExpHilsI2cTarget.cpp rename to src/Component/examples/example_i2c_target_for_hils.cpp index a1ac75e60..b71c35411 100644 --- a/src/Component/Abstract/ExpHilsI2cTarget.cpp +++ b/src/Component/examples/example_i2c_target_for_hils.cpp @@ -1,9 +1,9 @@ /** - * @file ExpHilsI2cTarget.cpp + * @file example_i2c_target_for_hils.cpp * @brief Example of component emulation for I2C target side communication in HILS environment */ -#include "ExpHilsI2cTarget.h" +#include "example_i2c_target_for_hils.hpp" ExpHilsI2cTarget::ExpHilsI2cTarget(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) diff --git a/src/Component/Abstract/ExpHilsI2cTarget.h b/src/Component/examples/example_i2c_target_for_hils.hpp similarity index 93% rename from src/Component/Abstract/ExpHilsI2cTarget.h rename to src/Component/examples/example_i2c_target_for_hils.hpp index e274621fa..1eb99a10e 100644 --- a/src/Component/Abstract/ExpHilsI2cTarget.h +++ b/src/Component/examples/example_i2c_target_for_hils.hpp @@ -1,13 +1,13 @@ /** - * @file ExpHilsI2cTarget.h + * @file example_i2c_target_for_hils.hpp * @brief Example of component emulation for I2C target side communication in HILS environment */ #pragma once #include -#include "ComponentBase.h" -#include "ObcI2cTargetCommunicationBase.h" +#include "../Abstract/ComponentBase.h" +#include "../Abstract/ObcI2cTargetCommunicationBase.h" /** * @class ExpHilsI2cTarget diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 2b3fdd15b..90185a1bf 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -4,7 +4,6 @@ */ #pragma once -#include #include #include #include @@ -23,6 +22,7 @@ #include #include #include +#include #include #include From 637c4b60380de6da17b198c5174f746a74738a68 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:07:56 +0100 Subject: [PATCH 0097/1086] Rename ExpHilsI2cTarget class --- .../examples/example_i2c_target_for_hils.cpp | 8 ++++---- .../examples/example_i2c_target_for_hils.hpp | 14 +++++++------- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 4 ++-- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/Component/examples/example_i2c_target_for_hils.cpp b/src/Component/examples/example_i2c_target_for_hils.cpp index b71c35411..aa81abc33 100644 --- a/src/Component/examples/example_i2c_target_for_hils.cpp +++ b/src/Component/examples/example_i2c_target_for_hils.cpp @@ -5,13 +5,13 @@ #include "example_i2c_target_for_hils.hpp" -ExpHilsI2cTarget::ExpHilsI2cTarget(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, - const unsigned int hils_port_id, HilsPortManager* hils_port_manager) +ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, + OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) : ComponentBase(prescaler, clock_gen), ObcI2cTargetCommunicationBase(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} -ExpHilsI2cTarget::~ExpHilsI2cTarget() {} +ExampleI2cTargetForHils::~ExampleI2cTargetForHils() {} -void ExpHilsI2cTarget::MainRoutine(int count) { +void ExampleI2cTargetForHils::MainRoutine(int count) { UNUSED(count); // update telemetry data diff --git a/src/Component/examples/example_i2c_target_for_hils.hpp b/src/Component/examples/example_i2c_target_for_hils.hpp index 1eb99a10e..ead2f338f 100644 --- a/src/Component/examples/example_i2c_target_for_hils.hpp +++ b/src/Component/examples/example_i2c_target_for_hils.hpp @@ -10,17 +10,17 @@ #include "../Abstract/ObcI2cTargetCommunicationBase.h" /** - * @class ExpHilsI2cTarget + * @class ExampleI2cTargetForHils * @brief Example of component emulation for I2C target side communication in HILS environment * @details Supposed to be used in connection with the following I2C-USB Controller converter * MFT200XD Data Sheet:https://www.ftdichip.com/Support/Documents/DataSheets/ICs/DS_FT200XD.pdf * Telemetry size = 5 bytes(ASCII) * Telemetry changes; ABCDE, BCDEF, ..., VWXYZ, ABCDE, ... */ -class ExpHilsI2cTarget : public ComponentBase, public ObcI2cTargetCommunicationBase { +class ExampleI2cTargetForHils : public ComponentBase, public ObcI2cTargetCommunicationBase { public: /** - * @fn ExpHilsI2cTarget + * @fn ExampleI2cTargetForHils * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_gen: Clock generator @@ -30,13 +30,13 @@ class ExpHilsI2cTarget : public ComponentBase, public ObcI2cTargetCommunicationB * @param [in] hils_port_id: ID of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ExpHilsI2cTarget(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, - const unsigned int hils_port_id, HilsPortManager* hils_port_manager); + ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, + const unsigned int hils_port_id, HilsPortManager* hils_port_manager); /** - * @fn ~ExpHilsI2cTarget + * @fn ~ExampleI2cTargetForHils * @brief Destructor */ - ~ExpHilsI2cTarget(); + ~ExampleI2cTargetForHils(); protected: // Override functions for ComponentBase diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 90185a1bf..9318722ff 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -102,8 +102,8 @@ class SampleComponents : public InstalledComponents { /* ExampleSerialCommunicationForHils* exp_hils_uart_responder_; //!< Example of HILS UART responder ExampleSerialCommunicationForHils* exp_hils_uart_sender_; //!< Example of HILS UART sender - ExampleI2cControllerForHils* exp_hils_i2c_controller_; //!< Example of HILS I2C controller - ExpHilsI2cTarget* exp_hils_i2c_target_; //!< Example of HILS I2C target + ExampleI2cControllerForHils* exp_hils_i2c_controller_; //!< Example of HILS I2C controller + ExampleI2cTargetForHils* exp_hils_i2c_target_; //!< Example of HILS I2C target */ // States From 822ed36c3afdfe5e984f4f4fdc368ffba5f167ee Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:12:05 +0100 Subject: [PATCH 0098/1086] Fix Sample Components --- .../SampleSpacecraft/SampleComponents.cpp | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp index 39a9af346..bee9509ba 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp @@ -78,24 +78,25 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur config_->main_logger_->CopyFileToLogDir(ini_path); antenna_ = new Antenna(InitAntenna(1, ini_path)); - // ChangeStructure: Please uncomment change_structure related codes if you want to test the change_structure - // change_structure_ = new ChangeStructure(clock_gen, structure_); - // PCU power port initial control pcu_->GetPowerPort(0)->SetVoltage(3.3); pcu_->GetPowerPort(1)->SetVoltage(3.3); pcu_->GetPowerPort(2)->SetVoltage(3.3); - // Examples of HILS + /** Examples **/ + + // ChangeStructure: Please uncomment change_structure related codes if you want to test the change_structure + // change_structure_ = new ChangeStructure(clock_gen, structure_); + // UART tutorial. Comment out when not in use. - // exp_hils_uart_responder_ = new ExpHils(clock_gen, 1, obc_, 3, 9600, - // hils_port_manager_, 1); exp_hils_uart_sender_ = new ExpHils(clock_gen, 0, - // obc_, 4, 9600, hils_port_manager_, 0); + // exp_hils_uart_responder_ = new ExampleSerialCommunicationForHils(clock_gen, 1, obc_, 3, 9600, hils_port_manager_, 1); + // exp_hils_uart_sender_ = new ExampleSerialCommunicationForHils(clock_gen, 0, obc_, 4, 9600, hils_port_manager_, 0); + // I2C tutorial. Comment out when not in use. - // exp_hils_i2c_controller_ = new ExpHilsI2cController( - // 30, clock_gen, 5, 115200, 256, 256, hils_port_manager_); - // exp_hils_i2c_target_ = - // new ExpHilsI2cTarget(1, clock_gen, 0, 0x44, obc_, 6, hils_port_manager_); + // exp_hils_i2c_controller_ = new ExampleI2cControllerForHils(30, clock_gen, 5, 115200, 256, 256, hils_port_manager_); + // exp_hils_i2c_target_ = new ExampleI2cTargetForHils(1, clock_gen, 0, 0x44, obc_, 6, hils_port_manager_); + + /**************/ // actuator debug output // libra::Vector mag_moment_c{0.01}; From 3fc4929d77710e1fec231e843ef7871ff60ae8b8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:15:42 +0100 Subject: [PATCH 0099/1086] Rename ChangeStructure --- src/Component/CMakeLists.txt | 2 +- .../{ChangeStructure.cpp => example_change_structure.cpp} | 4 ++-- .../{ChangeStructure.hpp => example_change_structure.hpp} | 2 +- src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename src/Component/examples/{ChangeStructure.cpp => example_change_structure.cpp} (92%) rename src/Component/examples/{ChangeStructure.hpp => example_change_structure.hpp} (97%) diff --git a/src/Component/CMakeLists.txt b/src/Component/CMakeLists.txt index 201897812..ed19f5ada 100644 --- a/src/Component/CMakeLists.txt +++ b/src/Component/CMakeLists.txt @@ -34,7 +34,7 @@ add_library(${PROJECT_NAME} STATIC CommGS/GScalculator.cpp CommGS/InitGsCalculator.cpp - examples/ChangeStructure.cpp + examples/example_change_structure.cpp examples/example_serial_communication_with_obc.cpp examples/example_serial_communication_for_hils.cpp examples/example_i2c_controller_for_hils.cpp diff --git a/src/Component/examples/ChangeStructure.cpp b/src/Component/examples/example_change_structure.cpp similarity index 92% rename from src/Component/examples/ChangeStructure.cpp rename to src/Component/examples/example_change_structure.cpp index 63383c6fc..fe6f77f46 100644 --- a/src/Component/examples/ChangeStructure.cpp +++ b/src/Component/examples/example_change_structure.cpp @@ -1,9 +1,9 @@ /** - * @file ChangeStructure.cpp + * @file example_change_structure.cpp * @brief Class to show an example to change satellite structure information */ -#include "ChangeStructure.hpp" +#include "example_change_structure.hpp" ChangeStructure::ChangeStructure(ClockGenerator* clock_gen, Structure* structure) : ComponentBase(1, clock_gen), structure_(structure) {} diff --git a/src/Component/examples/ChangeStructure.hpp b/src/Component/examples/example_change_structure.hpp similarity index 97% rename from src/Component/examples/ChangeStructure.hpp rename to src/Component/examples/example_change_structure.hpp index bea1a235d..629fa349f 100644 --- a/src/Component/examples/ChangeStructure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -1,5 +1,5 @@ /** - * @file ChangeStructure.hpp + * @file example_change_structure.hpp * @brief Class to show an example to change satellite structure information */ diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 9318722ff..6f2283de6 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -20,7 +20,7 @@ #include #include #include -#include +#include #include #include #include From 63bd9f6f31079facbcb7f5cc52390e3649252421 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:26:30 +0100 Subject: [PATCH 0100/1086] Rename ChangeStructure class --- .../examples/example_change_structure.cpp | 11 ++++++----- .../examples/example_change_structure.hpp | 15 ++++++--------- .../SampleSpacecraft/SampleComponents.cpp | 2 +- .../SampleSpacecraft/SampleComponents.h | 2 +- 4 files changed, 14 insertions(+), 16 deletions(-) diff --git a/src/Component/examples/example_change_structure.cpp b/src/Component/examples/example_change_structure.cpp index fe6f77f46..15d2f5775 100644 --- a/src/Component/examples/example_change_structure.cpp +++ b/src/Component/examples/example_change_structure.cpp @@ -5,11 +5,12 @@ #include "example_change_structure.hpp" -ChangeStructure::ChangeStructure(ClockGenerator* clock_gen, Structure* structure) : ComponentBase(1, clock_gen), structure_(structure) {} +ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure) + : ComponentBase(1, clock_gen), structure_(structure) {} -ChangeStructure::~ChangeStructure() {} +ExampleChangeStructure::~ExampleChangeStructure() {} -void ChangeStructure::MainRoutine(int count) { +void ExampleChangeStructure::MainRoutine(int count) { if (count > 1000) { // Mass structure_->GetToSetKinematicsParams().SetMass_kg(100.0); @@ -30,13 +31,13 @@ void ChangeStructure::MainRoutine(int count) { } } -std::string ChangeStructure::GetLogHeader() const { +std::string ExampleChangeStructure::GetLogHeader() const { std::string str_tmp = ""; return str_tmp; } -std::string ChangeStructure::GetLogValue() const { +std::string ExampleChangeStructure::GetLogValue() const { std::string str_tmp = ""; return str_tmp; diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 629fa349f..8993b0ddd 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -3,8 +3,7 @@ * @brief Class to show an example to change satellite structure information */ -#ifndef CHANGE_STRUCTURE_H_ -#define CHANGE_STRUCTURE_H_ +#pragma once #include #include @@ -12,23 +11,23 @@ #include "../Abstract/ComponentBase.h" /** - * @class ChangeStructure + * @class ExampleChangeStructure * @brief Class to show an example to change satellite structure information */ -class ChangeStructure : public ComponentBase, public ILoggable { +class ExampleChangeStructure : public ComponentBase, public ILoggable { public: /** - * @fn ChangeStructure + * @fn ExampleChangeStructure * @brief Constructor with power port * @param [in] clock_gen: Clock generator * @param [in] structure: Structure information */ - ChangeStructure(ClockGenerator* clock_gen, Structure* structure); + ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure); /** * @fn ~ChangeStructure * @brief Destructor */ - ~ChangeStructure(); + ~ExampleChangeStructure(); // Override functions for ComponentBase /** @@ -52,5 +51,3 @@ class ChangeStructure : public ComponentBase, public ILoggable { protected: Structure* structure_; //!< Structure information }; - -#endif diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp index bee9509ba..ee8074680 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp @@ -86,7 +86,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur /** Examples **/ // ChangeStructure: Please uncomment change_structure related codes if you want to test the change_structure - // change_structure_ = new ChangeStructure(clock_gen, structure_); + // change_structure_ = new ExampleChangeStructure(clock_gen, structure_); // UART tutorial. Comment out when not in use. // exp_hils_uart_responder_ = new ExampleSerialCommunicationForHils(clock_gen, 1, obc_, 3, 9600, hils_port_manager_, 1); diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 6f2283de6..954ed052e 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -98,7 +98,7 @@ class SampleComponents : public InstalledComponents { Antenna* antenna_; //!< Antenna // Examples - // ChangeStructure* change_structure_; //!< Change structure + // ExampleChangeStructure* change_structure_; //!< Change structure /* ExampleSerialCommunicationForHils* exp_hils_uart_responder_; //!< Example of HILS UART responder ExampleSerialCommunicationForHils* exp_hils_uart_sender_; //!< Example of HILS UART sender From afc09d5bfdb4f6cef7bdfe1186e42a12349830be Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 3 Feb 2023 19:31:03 +0100 Subject: [PATCH 0101/1086] Fix format --- src/Component/examples/example_i2c_controller_for_hils.cpp | 4 ++-- src/Component/examples/example_i2c_controller_for_hils.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/Component/examples/example_i2c_controller_for_hils.cpp b/src/Component/examples/example_i2c_controller_for_hils.cpp index b86298678..c22f20180 100644 --- a/src/Component/examples/example_i2c_controller_for_hils.cpp +++ b/src/Component/examples/example_i2c_controller_for_hils.cpp @@ -5,8 +5,8 @@ #include "example_i2c_controller_for_hils.hpp" ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, - const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, - HilsPortManager* hils_port_manager) + const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, + HilsPortManager* hils_port_manager) : ComponentBase(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buf_size, rx_buf_size, hils_port_manager) {} ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} diff --git a/src/Component/examples/example_i2c_controller_for_hils.hpp b/src/Component/examples/example_i2c_controller_for_hils.hpp index e55f6062d..8379ba0ca 100644 --- a/src/Component/examples/example_i2c_controller_for_hils.hpp +++ b/src/Component/examples/example_i2c_controller_for_hils.hpp @@ -29,7 +29,7 @@ class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCo * @param [in] hils_port_manager: HILS port manager */ ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, - const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager); + const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cControllerForHils * @brief Destructor From 661f61c270af0d419cf8a918cf3d67c40d8bf92e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 15:00:05 +0100 Subject: [PATCH 0102/1086] Add initialize function for PowerPort --- src/Interface/SpacecraftInOut/Ports/PowerPort.cpp | 12 ++++++++++++ src/Interface/SpacecraftInOut/Ports/PowerPort.h | 7 +++++++ 2 files changed, 19 insertions(+) diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp index 8d78da6d8..905079984 100644 --- a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -5,6 +5,8 @@ #include "PowerPort.h" +#include + #include PowerPort::PowerPort() : kPortId(-1), current_limit_(10.0), minimum_voltage_(3.3), assumed_power_consumption_(0.0) { @@ -58,3 +60,13 @@ void PowerPort::SubtractAssumedPowerConsumption(const double power) { if (assumed_power_consumption_ < 0.0) assumed_power_consumption_ = 0.0; return; } + +void PowerPort::InitializeWithInitializeFile(const std::string file_name) { + IniAccess initialize_file(file_name); + const std::string section_name = "PowerPort"; + + double minimum_voltage = initialize_file.ReadInt(section_name.c_str(), "minimum_voltage_V"); + this->SetMinimumVoltage(minimum_voltage); + double assumed_power_consumption = initialize_file.ReadInt(section_name.c_str(), "assumed_power_consumption_W"); + this->SetAssumedPowerConsumption(assumed_power_consumption); +} diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.h b/src/Interface/SpacecraftInOut/Ports/PowerPort.h index 060aebabe..686518b2c 100644 --- a/src/Interface/SpacecraftInOut/Ports/PowerPort.h +++ b/src/Interface/SpacecraftInOut/Ports/PowerPort.h @@ -5,6 +5,8 @@ #pragma once +#include + /** * @class PowerPort * @brief Class to emulate electrical power port @@ -104,6 +106,11 @@ class PowerPort { * @brief Subtract assumed power consumption [W] to emulate power line which has multiple loads */ void SubtractAssumedPowerConsumption(const double power); + /** + * @fn InitializeWithInitializeFile + * @brief Initialize PowerPort class with initialize file + */ + void InitializeWithInitializeFile(const std::string file_name); private: // PCU setting parameters From 5add9ebfac6b0131369b2130f99fe8d79bca8f66 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 15:07:29 +0100 Subject: [PATCH 0103/1086] Fix to use power port initialize function for gyro sensor --- data/sample/initialize_files/components/gyro_sensor.ini | 2 +- src/Component/AOCS/InitGyro.cpp | 7 ++----- 2 files changed, 3 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index ce769a504..7838194a0 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -45,6 +45,6 @@ random_walk_standard_deviation_c_rad_s(2) = 1e-3 range_to_constant_rad_s = 5.0 // smaller than Range_to_zero range_to_zero_rad_s = 10.0 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 328a97f33..89955f988 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -39,11 +39,8 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); // PowerPort - double minimum_voltage = gyro_conf.ReadDouble(GSection, "minimum_voltage_V"); - power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = gyro_conf.ReadDouble(GSection, "assumed_power_consumption_W"); - power_port->SetAssumedPowerConsumption(assumed_power_consumption); - + power_port->InitializeWithInitializeFile(fname); + Gyro gyro(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } From 8856e761ad5cb4964b79c2f6bf3fa649c293f380 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:13:26 +0100 Subject: [PATCH 0104/1086] Fix to use double --- src/Interface/SpacecraftInOut/Ports/PowerPort.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp index 905079984..732cb28f5 100644 --- a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -65,8 +65,8 @@ void PowerPort::InitializeWithInitializeFile(const std::string file_name) { IniAccess initialize_file(file_name); const std::string section_name = "PowerPort"; - double minimum_voltage = initialize_file.ReadInt(section_name.c_str(), "minimum_voltage_V"); + double minimum_voltage = initialize_file.ReadDouble(section_name.c_str(), "minimum_voltage_V"); this->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = initialize_file.ReadInt(section_name.c_str(), "assumed_power_consumption_W"); + double assumed_power_consumption = initialize_file.ReadDouble(section_name.c_str(), "assumed_power_consumption_W"); this->SetAssumedPowerConsumption(assumed_power_consumption); } From fb67b3e90ff97cab5cd496a8db6de3d83c915c9a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:13:42 +0100 Subject: [PATCH 0105/1086] Fix to use power port initialize function for magnetometer --- data/sample/initialize_files/components/magnetometer.ini | 2 +- src/Component/AOCS/InitMagSensor.cpp | 5 +---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/data/sample/initialize_files/components/magnetometer.ini b/data/sample/initialize_files/components/magnetometer.ini index d309feaac..70a493295 100644 --- a/data/sample/initialize_files/components/magnetometer.ini +++ b/data/sample/initialize_files/components/magnetometer.ini @@ -45,6 +45,6 @@ normal_random_standard_deviation_c_nT(2) = 10.0 range_to_constant_nT = 1.0e6 // smaller than Range_to_zero range_to_zero_nT = 1.5e6 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index 0b87ac0ac..7bb8d5059 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -39,10 +39,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Magnetometer", "nT"); // PowerPort - double minimum_voltage = magsensor_conf.ReadDouble(MSSection, "minimum_voltage_V"); - power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = magsensor_conf.ReadDouble(MSSection, "assumed_power_consumption_W"); - power_port->AddAssumedPowerConsumption(assumed_power_consumption); + power_port->InitializeWithInitializeFile(fname); MagSensor magsensor(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, magnet); return magsensor; From d3c02d9e6c758d6775504954217a258e4a51abe5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:16:28 +0100 Subject: [PATCH 0106/1086] Fix to use power port initialize function for gnss receiver --- data/sample/initialize_files/components/gnss_receiver.ini | 2 +- src/Component/AOCS/InitGnssReceiver.cpp | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/gnss_receiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini index 41197c32a..ae53e651c 100644 --- a/data/sample/initialize_files/components/gnss_receiver.ini +++ b/data/sample/initialize_files/components/gnss_receiver.ini @@ -38,6 +38,6 @@ white_noise_standard_deviation_eci_m(0) = 10000.0 white_noise_standard_deviation_eci_m(1) = 1000.0 white_noise_standard_deviation_eci_m(2) = 1000.0 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index 980ba0b5a..def44c130 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -60,6 +60,9 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, const GnssSatellites* gnss_satellites, const SimTime* simtime) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites); + // PowerPort + power_port->InitializeWithInitializeFile(fname); + GNSSReceiver gnss_r(gr_param.prescaler, clock_gen, power_port, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); return gnss_r; From f111a2c6d0c6749715a8ecda761cbeb72200fa8a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:17:58 +0100 Subject: [PATCH 0107/1086] Fix to use power port initialize function for magnetorquer --- data/sample/initialize_files/components/magnetorquer.ini | 2 +- src/Component/AOCS/InitMagTorquer.cpp | 5 +---- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/data/sample/initialize_files/components/magnetorquer.ini b/data/sample/initialize_files/components/magnetorquer.ini index ad6fbad5c..53a511343 100644 --- a/data/sample/initialize_files/components/magnetorquer.ini +++ b/data/sample/initialize_files/components/magnetorquer.ini @@ -49,6 +49,6 @@ white_noise_standard_deviation_c_Am2(0) = 0.0 white_noise_standard_deviation_c_Am2(1) = 0.0 white_noise_standard_deviation_c_Am2(2) = 0.0 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index c38d9ecd4..928a4dd04 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -86,10 +86,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); // PowerPort - double minimum_voltage = magtorquer_conf.ReadDouble(MTSection, "minimum_voltage_V"); - power_port->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = magtorquer_conf.ReadDouble(MTSection, "assumed_power_consumption_W"); - power_port->SetAssumedPowerConsumption(assumed_power_consumption); + power_port->InitializeWithInitializeFile(fname); MagTorquer magtorquer(prescaler, clock_gen, power_port, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); From 3ac5cbba656d67fc43fdf909d509270d78b06f7a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:19:53 +0100 Subject: [PATCH 0108/1086] Fix to use power port initialize function for reaction wheel --- data/sample/initialize_files/components/reaction_wheel.ini | 2 +- src/Component/AOCS/InitRwModel.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/reaction_wheel.ini b/data/sample/initialize_files/components/reaction_wheel.ini index d7345cdb8..8fb4e5e66 100644 --- a/data/sample/initialize_files/components/reaction_wheel.ini +++ b/data/sample/initialize_files/components/reaction_wheel.ini @@ -60,6 +60,6 @@ structural_resonance_frequency_Hz = 585.0 //[Hz] damping_factor = 0.1 //[ ] bandwidth = 0.001 //[ ] -// Power Port +[PowerPort] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index 418614e7e..4093c67f4 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -113,6 +113,8 @@ RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuat double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); + power_port->InitializeWithInitializeFile(file_name); + RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, From 97f871a88e4e3551ca7840628e8f46c66fd1ec77 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:22:05 +0100 Subject: [PATCH 0109/1086] Fix to use power port initialize function for star sensor --- data/sample/initialize_files/components/star_sensor.ini | 2 +- src/Component/AOCS/InitStt.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/star_sensor.ini b/data/sample/initialize_files/components/star_sensor.ini index b9d531cbe..fc9219f6e 100644 --- a/data/sample/initialize_files/components/star_sensor.ini +++ b/data/sample/initialize_files/components/star_sensor.ini @@ -32,6 +32,6 @@ moon_forbidden_angle_deg = 10 // Limit angular rate to capture stars[deg/s] angular_rate_limit_deg_s = 10.0 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index 1b4c4b673..472e375b2 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -68,6 +68,8 @@ STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, con double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; + power_port->InitializeWithInitializeFile(fname); + STT stt(prescaler, clock_gen, power_port, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); return stt; From 50522dfbc97a321f5d4d6f2fa4c4fbe5ae806c68 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:23:56 +0100 Subject: [PATCH 0110/1086] Fix to use power port initialize function for sun sensor --- data/sample/initialize_files/components/sun_sensor.ini | 2 +- src/Component/AOCS/InitSunSensor.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/sun_sensor.ini b/data/sample/initialize_files/components/sun_sensor.ini index a84bb5f89..c6235e66f 100644 --- a/data/sample/initialize_files/components/sun_sensor.ini +++ b/data/sample/initialize_files/components/sun_sensor.ini @@ -22,6 +22,6 @@ bias_standard_deviation_deg = 0.5 // If it becomes smaller than this, it becomes impossible to get the sun direction intensity_lower_threshold_percent = 30.0 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index 3df68b0f9..c7417891b 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -71,6 +71,8 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss double intensity_lower_threshold_percent; intensity_lower_threshold_percent = ss_conf.ReadDouble(Section, "intensity_lower_threshold_percent"); + power_port->InitializeWithInitializeFile(file_name); + SunSensor ss(prescaler, clock_gen, power_port, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, srp, local_celes_info); return ss; From b69831aa79b0a6bc40f45b94925f16d24cd5da05 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:26:19 +0100 Subject: [PATCH 0111/1086] Fix to use power port initialize function for thruster --- data/sample/initialize_files/components/thruster.ini | 2 +- src/Component/Propulsion/InitSimpleThruster.cpp | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/thruster.ini b/data/sample/initialize_files/components/thruster.ini index c2b752e3e..efc365431 100644 --- a/data/sample/initialize_files/components/thruster.ini +++ b/data/sample/initialize_files/components/thruster.ini @@ -20,6 +20,6 @@ thrust_error_standard_deviation_N = 0.001 // Standard deviation of thrust direction error [deg] direction_error_standard_deviation_deg = 1 -// Power Port +[PowerPort] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 14ab13e1b..412955032 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -58,6 +58,8 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_po double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; + power_port->InitializeWithInitializeFile(fname); + SimpleThruster thruster(prescaler, clock_gen, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); return thruster; } From 6ab990b594bd266388a642947b60907ad773478e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 16:28:29 +0100 Subject: [PATCH 0112/1086] Fix format --- src/Component/AOCS/InitGyro.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 89955f988..62b1da861 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -40,7 +40,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c // PowerPort power_port->InitializeWithInitializeFile(fname); - + Gyro gyro(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } From 820b9c9fa9843184e82145b6b939d5adf8cc07a8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 4 Feb 2023 17:08:17 +0100 Subject: [PATCH 0113/1086] Fix st_sensor_id to sensor_id or actuator_id --- src/Component/AOCS/Gyro.cpp | 4 ++-- src/Component/AOCS/MagSensor.cpp | 4 ++-- src/Component/AOCS/MagTorquer.cpp | 4 ++-- src/Component/AOCS/SunSensor.cpp | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/Component/AOCS/Gyro.cpp b/src/Component/AOCS/Gyro.cpp index 5b93b4544..c23ddaa9d 100644 --- a/src/Component/AOCS/Gyro.cpp +++ b/src/Component/AOCS/Gyro.cpp @@ -26,8 +26,8 @@ void Gyro::MainRoutine(int count) { std::string Gyro::GetLogHeader() const { std::string str_tmp = ""; - const std::string st_sensor_id = std::to_string(static_cast(sensor_id_)); - std::string sensor_name = "gyro_sensor" + st_sensor_id + "_"; + const std::string sensor_id = std::to_string(static_cast(sensor_id_)); + std::string sensor_name = "gyro_sensor" + sensor_id + "_"; str_tmp += WriteVector(sensor_name + "measured_angular_velocity", "c", "rad/s", kGyroDim); return str_tmp; diff --git a/src/Component/AOCS/MagSensor.cpp b/src/Component/AOCS/MagSensor.cpp index 8cf5c625a..2c887d481 100644 --- a/src/Component/AOCS/MagSensor.cpp +++ b/src/Component/AOCS/MagSensor.cpp @@ -23,8 +23,8 @@ void MagSensor::MainRoutine(int count) { std::string MagSensor::GetLogHeader() const { std::string str_tmp = ""; - const std::string st_sensor_id = std::to_string(static_cast(sensor_id_)); - std::string sensor_name = "magnetometer" + st_sensor_id + "_"; + const std::string sensor_id = std::to_string(static_cast(sensor_id_)); + std::string sensor_name = "magnetometer" + sensor_id + "_"; str_tmp += WriteVector(sensor_name + "measured_magnetic_field", "c", "nT", kMagDim); return str_tmp; diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/Component/AOCS/MagTorquer.cpp index 79e33fd12..e9576775e 100644 --- a/src/Component/AOCS/MagTorquer.cpp +++ b/src/Component/AOCS/MagTorquer.cpp @@ -84,8 +84,8 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { std::string MagTorquer::GetLogHeader() const { std::string str_tmp = ""; - const std::string st_sensor_id = std::to_string(static_cast(id_)); - std::string actuator_name = "magnetorquer" + st_sensor_id + "_"; + const std::string actuator_id = std::to_string(static_cast(id_)); + std::string actuator_name = "magnetorquer" + actuator_id + "_"; str_tmp += WriteVector(actuator_name + "output_magnetic_moment", "b", "Am2", kMtqDim); str_tmp += WriteVector(actuator_name + "output_torque", "b", "Nm", kMtqDim); diff --git a/src/Component/AOCS/SunSensor.cpp b/src/Component/AOCS/SunSensor.cpp index 8ba8b990e..0b6602267 100644 --- a/src/Component/AOCS/SunSensor.cpp +++ b/src/Component/AOCS/SunSensor.cpp @@ -130,8 +130,8 @@ double SunSensor::TanRange(double x) { string SunSensor::GetLogHeader() const { string str_tmp = ""; - const string st_id = std::to_string(static_cast(id_)); - std::string sensor_name = "sun_sensor" + st_id + "_"; + const string sensor_id = std::to_string(static_cast(id_)); + std::string sensor_name = "sun_sensor" + sensor_id + "_"; str_tmp += WriteVector(sensor_name + "measured_sun_direction", "c", "-", 3); str_tmp += WriteScalar(sensor_name + "sun_detected_flag", "-"); From dbeead9328ee4984c7b2fd15ab1d0c5a7842ca90 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 08:24:43 +0100 Subject: [PATCH 0114/1086] Modify to use exclusion angle --- src/Component/Mission/Telescope/Telescope.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/Component/Mission/Telescope/Telescope.cpp b/src/Component/Mission/Telescope/Telescope.cpp index f72d33c84..c100cd68d 100644 --- a/src/Component/Mission/Telescope/Telescope.cpp +++ b/src/Component/Mission/Telescope/Telescope.cpp @@ -153,9 +153,9 @@ string Telescope::GetLogHeader() const { std::string component_name = "telescope_"; - str_tmp += WriteScalar(component_name + "sun_in_forbidden_angle", ""); - str_tmp += WriteScalar(component_name + "earth_in_forbidden_angle", ""); - str_tmp += WriteScalar(component_name + "moon_in_forbidden_angle", ""); + str_tmp += WriteScalar(component_name + "sun_in_exclusion_angle", ""); + str_tmp += WriteScalar(component_name + "earth_in_exclusion_angle", ""); + str_tmp += WriteScalar(component_name + "moon_in_exclusion_angle", ""); str_tmp += WriteVector(component_name + "sun_position", "img", "pix", 2); str_tmp += WriteVector(component_name + "earth_position", "img", "pix", 2); str_tmp += WriteVector(component_name + "moon_position", "img", "pix", 2); From e00c791f796e5185808dbda4eeb688e07f509715 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 08:54:18 +0100 Subject: [PATCH 0115/1086] Modify to use exclusion angle instead of fobidden angle --- .../initialize_files/components/star_sensor.ini | 10 +++++----- .../sample/initialize_files/components/telescope.ini | 12 ++++++------ src/Component/AOCS/InitStt.cpp | 12 ++++++------ src/Component/Mission/Telescope/InitTelescope.cpp | 6 +++--- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/data/sample/initialize_files/components/star_sensor.ini b/data/sample/initialize_files/components/star_sensor.ini index fc9219f6e..c555a4684 100644 --- a/data/sample/initialize_files/components/star_sensor.ini +++ b/data/sample/initialize_files/components/star_sensor.ini @@ -20,14 +20,14 @@ output_delay_s = 1 // Output Interval [sec] output_interval_s = 1 -// Sun forbidden harf angle [deg] -sun_forbidden_angle_deg = 10 +// Sun exclusion harf angle [deg] +sun_exclusion_angle_deg = 10 -// Earth forbidden harf angle [deg] -earth_forbidden_angle_deg = 10 +// Earth exclusion harf angle [deg] +earth_exclusion_angle_deg = 10 // Moon forbidden harf angle [deg] -moon_forbidden_angle_deg = 10 +moon_exclusion_angle_deg = 10 // Limit angular rate to capture stars[deg/s] angular_rate_limit_deg_s = 10.0 diff --git a/data/sample/initialize_files/components/telescope.ini b/data/sample/initialize_files/components/telescope.ini index 78bb71124..28bf4908a 100644 --- a/data/sample/initialize_files/components/telescope.ini +++ b/data/sample/initialize_files/components/telescope.ini @@ -8,14 +8,14 @@ quaternion_b2c(1) = 0 quaternion_b2c(2) = 0 quaternion_b2c(3) = 1 -// Sun forbidden angle [0, 90] -sun_forbidden_angle_deg = 60 +// Sun exclusion angle [0, 90] +sun_exclusion_angle_deg = 60 -// Earth forbidden angle [0, 90] -earth_forbidden_angle_deg = 60 +// Earth exclusion angle [0, 90] +earth_exclusion_angle_deg = 60 -// Moon forbidden angle [0, 90] -moon_forbidden_angle_deg = 60 +// Moon exclusion angle [0, 90] +moon_exclusion_angle_deg = 60 // Number of pixel in the X direction of image sensor x_number_of_pixel = 2048 diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index 472e375b2..e77fe7139 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -27,11 +27,11 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double int output_delay = max(int(output_delay_sec / step_time), 1); double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); int output_interval = max(int(output_interval_sec / step_time), 1); - double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle_deg"); + double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; - double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle_deg"); + double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_exclusion_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * libra::pi / 180.0; - double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle_deg"); + double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_exclusion_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * libra::pi / 180.0; double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; @@ -59,11 +59,11 @@ STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, con int output_delay = max(int(output_delay_sec / step_time), 1); double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); int output_interval = max(int(output_interval_sec / step_time), 1); - double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_forbidden_angle_deg"); + double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; - double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_forbidden_angle_deg"); + double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_exclusion_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * libra::pi / 180.0; - double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_forbidden_angle_deg"); + double moon_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "moon_exclusion_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * libra::pi / 180.0; double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index f14d67c79..6a7b0eba1 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -31,11 +31,11 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string f Quaternion q_b2c; Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", q_b2c); - double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_forbidden_angle_deg"); + double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * pi / 180; // deg to rad - double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_forbidden_angle_deg"); + double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_exclusion_angle_deg"); double earth_forbidden_angle_rad = earth_forbidden_angle_deg * pi / 180; // deg to rad - double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_forbidden_angle_deg"); + double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_exclusion_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * pi / 180; // deg to rad int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); From d8e3445255d87bbd87aa47fc84a3a67d87587591 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:16:56 +0100 Subject: [PATCH 0116/1086] Fix CSV file path --- .../initialize_files/components/ground_station_antenna.ini | 4 ++-- data/sample/initialize_files/components/reaction_wheel.ini | 4 ++-- .../sample/initialize_files/components/spacecraft_antenna.ini | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index 13afaca41..5f4c7c623 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -36,7 +36,7 @@ tx_antenna_gain_model = ISOTROPIC tx_gain_dBi = 12.0 // Antenna radiation pattern CSV file path -tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv +tx_antenna_radiation_pattern_file = .../../data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv // General information of the CSV file tx_length_theta = 360 tx_length_phi = 181 @@ -64,7 +64,7 @@ rx_antenna_gain_model = ISOTROPIC rx_gain_dBi = 43.27 // Antenna radiation pattern CSV file path -rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv +rx_antenna_radiation_pattern_file = ../../data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv // General information of the CSV file rx_length_theta = 360 rx_length_phi = 181 diff --git a/data/sample/initialize_files/components/reaction_wheel.ini b/data/sample/initialize_files/components/reaction_wheel.ini index 8fb4e5e66..40ac4f460 100644 --- a/data/sample/initialize_files/components/reaction_wheel.ini +++ b/data/sample/initialize_files/components/reaction_wheel.ini @@ -52,8 +52,8 @@ initial_angular_velocity_rad_s = 0.0 //Parameters for calculate RW jitter jitter_calculation = DISABLE jitter_logging = DISABLE -radial_force_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance/radial_force_harmonics_coefficients.csv -radial_torque_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance/radial_torque_harmonics_coefficients.csv +radial_force_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance_csv_files/radial_force_harmonics_coefficients.csv +radial_torque_harmonics_coefficient_file = ../../data/sample/initialize_files/components/rw_disturbance_csv_files/radial_torque_harmonics_coefficients.csv harmonics_degree = 12 considers_structural_resonance = DISABLE structural_resonance_frequency_Hz = 585.0 //[Hz] diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 3228e6347..602455659 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -36,7 +36,7 @@ tx_antenna_gain_model = RADIATION_PATTERN_CSV tx_gain_dBi = 8.0 // Antenna radiation pattern CSV file path -tx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv +tx_antenna_radiation_pattern_file = ../../data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv // General information of the CSV file tx_length_theta = 360 tx_length_phi = 181 @@ -64,7 +64,7 @@ rx_antenna_gain_model = RADIATION_PATTERN_CSV rx_gain_dBi = 43.27 // Antenna radiation pattern CSV file path -rx_antenna_radiation_pattern_file = ../../data/SampleSat/ini/component/AntennaRadiationPatternCsv/SampleAntennaRadiationPattern.csv +rx_antenna_radiation_pattern_file = ../../data/sample/initialize_files/components/antenna_radiation_pattern_csv_files/sample_antenna_radiation_pattern.csv // General information of the CSV file rx_length_theta = 360 rx_length_phi = 181 From b195efd2e6513b54174354649c9715c582953dff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:17:13 +0100 Subject: [PATCH 0117/1086] Fix to use SNAKE_CASE for simulation base --- .../initialize_files/sample_simulation_base.ini | 16 ++++++++-------- src/Environment/Global/InitGlobalEnvironment.cpp | 8 ++++---- src/Interface/LogOutput/InitLog.cpp | 8 ++++---- src/Simulation/Case/SimulationCase.cpp | 4 ++-- src/Simulation/MCSim/InitMcSim.cpp | 4 ++-- 5 files changed, 20 insertions(+), 20 deletions(-) diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 6c88d3cde..185a41fdd 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -1,4 +1,4 @@ -[Time] +[TIME] // Simulation start time [UTC] simulation_start_time_utc = 2020/01/01 12:00:00.0 @@ -44,7 +44,7 @@ log_output_period_s = 0.1 // should be larger than 'simulation_step_s' simulation_speed_setting = 0 -[MonteCarloExecution] +[MONTE_CARLO_EXECUTION] // Whether Monte-Carlo Simulation is executed or not monte_carlo_enable = DISABLE @@ -55,7 +55,7 @@ log_enable = ENABLE number_of_executions = 100 -[MonteCarloRandomization] +[MONTE_CARLO_RANDOMIZATION] parameter(0) = attitude0.debug attitude0.debug.randomization_type = CartesianUniform attitude0.debug.mean_or_min(0) = 0.0 @@ -75,7 +75,7 @@ attitude0.omega_b.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] attitude0.omega_b.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] -[CelestialInformation] +[CELESTIAL_INFORMATION] // Whether global celestial information is logged or not logging = ENABLE @@ -103,7 +103,7 @@ selected_body_name(8) = URANUS selected_body_name(9) = NEPTUNE selected_body_name(10) = PLUTO -[CspiceKernels] +[CSPICE_KERNELS] // CSPICE Kernel files definition tls = ../../../ExtLibraries/cspice/generic_kernels/lsk/naif0010.tls tpc1 = ../../../ExtLibraries/cspice/generic_kernels/pck/de-403-masses.tpc @@ -112,19 +112,19 @@ tpc3 = ../../../ExtLibraries/cspice/generic_kernels/pck/pck00010.tpc bsp = ../../../ExtLibraries/cspice/generic_kernels/spk/planets/de430.bsp -[HipparcosCatalogue] +[HIPPARCOS_CATALOGUE] catalogue_file_path = ../../../ExtLibraries/HipparcosCatalogue/hip_main.csv max_magnitude = 3.0 // Max magnitude to read from Hip catalog calculation = DISABLE logging = DISABLE -[Randomize] +[RANDOMIZE] // Seed of randam. When this value is 0, the seed will be varied by time. rand_seed = 0x11223344 -[SimulationSetting] +[SIMULATION_SETTINGS] // Whether the ini files are saved or not save_initialize_files = ENABLE diff --git a/src/Environment/Global/InitGlobalEnvironment.cpp b/src/Environment/Global/InitGlobalEnvironment.cpp index 2f7a7d8b1..17c02c2ce 100644 --- a/src/Environment/Global/InitGlobalEnvironment.cpp +++ b/src/Environment/Global/InitGlobalEnvironment.cpp @@ -16,7 +16,7 @@ SimTime* InitSimTime(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "Time"; + const char* section = "TIME"; // Parameters about entire simulation std::string start_ymdhms = ini_file.ReadString(section, "simulation_start_time_utc"); double end_sec = ini_file.ReadDouble(section, "simulation_duration_s"); @@ -47,7 +47,7 @@ SimTime* InitSimTime(std::string file_name) { HipparcosCatalogue* InitHipCatalogue(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "HipparcosCatalogue"; + const char* section = "HIPPARCOS_CATALOGUE"; std::string catalogue_path = ini_file.ReadString(section, "catalogue_file_path"); double max_magnitude = ini_file.ReadDouble(section, "max_magnitude"); @@ -63,8 +63,8 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name) { CelestialInformation* InitCelesInfo(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "CelestialInformation"; - const char* furnsh_section = "CspiceKernels"; + const char* section = "CELESTIAL_INFORMATION"; + const char* furnsh_section = "CSPICE_KERNELS"; // Read SPICE setting std::string inertial_frame = ini_file.ReadString(section, "inertial_frame"); diff --git a/src/Interface/LogOutput/InitLog.cpp b/src/Interface/LogOutput/InitLog.cpp index 2191a285a..e4cd82e03 100644 --- a/src/Interface/LogOutput/InitLog.cpp +++ b/src/Interface/LogOutput/InitLog.cpp @@ -10,8 +10,8 @@ Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); - std::string log_file_path = ini_file.ReadString("SimulationSetting", "log_file_save_directory"); - bool log_ini = ini_file.ReadEnable("SimulationSetting", "save_initialize_files"); + std::string log_file_path = ini_file.ReadString("SIMULATION_SETTINGS", "log_file_save_directory"); + bool log_ini = ini_file.ReadEnable("SIMULATION_SETTINGS", "save_initialize_files"); Logger* log = new Logger("default.csv", log_file_path, file_name, log_ini, true); @@ -21,8 +21,8 @@ Logger* InitLog(std::string file_name) { Logger* InitLogMC(std::string file_name, bool enable) { IniAccess ini_file(file_name); - std::string log_file_path = ini_file.ReadString("SimulationSetting", "log_file_save_directory"); - bool log_ini = ini_file.ReadEnable("SimulationSetting", "save_initialize_files"); + std::string log_file_path = ini_file.ReadString("SIMULATION_SETTINGS", "log_file_save_directory"); + bool log_ini = ini_file.ReadEnable("SIMULATION_SETTINGS", "save_initialize_files"); Logger* log = new Logger("mont.csv", log_file_path, file_name, log_ini, enable); diff --git a/src/Simulation/Case/SimulationCase.cpp b/src/Simulation/Case/SimulationCase.cpp index 402df2ed2..af4e5b6d2 100644 --- a/src/Simulation/Case/SimulationCase.cpp +++ b/src/Simulation/Case/SimulationCase.cpp @@ -12,7 +12,7 @@ SimulationCase::SimulationCase(std::string ini_base) { IniAccess simbase_ini = IniAccess(ini_base); - const char* section = "SimulationSetting"; + const char* section = "SIMULATION_SETTINGS"; sim_config_.ini_base_fname_ = ini_base; sim_config_.main_logger_ = InitLog(sim_config_.ini_base_fname_); sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); @@ -24,7 +24,7 @@ SimulationCase::SimulationCase(std::string ini_base) { } SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); - const char* section = "SimulationSetting"; + const char* section = "SIMULATION_SETTINGS"; sim_config_.ini_base_fname_ = ini_base; // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(mc_sim.GetNumOfExecutionsDone()) + ".csv"; diff --git a/src/Simulation/MCSim/InitMcSim.cpp b/src/Simulation/MCSim/InitMcSim.cpp index debb4b653..50429dd2e 100644 --- a/src/Simulation/MCSim/InitMcSim.cpp +++ b/src/Simulation/MCSim/InitMcSim.cpp @@ -13,7 +13,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { IniAccess ini_file(file_name); - const char* section = "MonteCarloExecution"; + const char* section = "MONTE_CARLO_EXECUTION"; unsigned long long total_num_of_executions = ini_file.ReadInt(section, "number_of_executions"); @@ -25,7 +25,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { bool log_history = ini_file.ReadEnable(section, "log_enable"); mc_sim->LogHistory(log_history); - section = "MonteCarloRandomization"; + section = "MONTE_CARLO_RANDOMIZATION"; std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "parameter"); std::vector so_str_vec, ip_str_vec; From 2bfc3af5a5fa581a6adc36c3c27da9cf860ae2a9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:20:42 +0100 Subject: [PATCH 0118/1086] Fix to use SNAKE_CASE for disturbance --- data/sample/initialize_files/sample_disturbance.ini | 6 +++--- src/Disturbance/InitDisturbance.cpp | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index afd4212a4..bac0ddc21 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -6,13 +6,13 @@ degree = 4 coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii -[MAG_DISTURBANCE] +[MAGNETIC_DISTURBANCE] // Enable only when the center object is defined as the Earth calculation = ENABLE logging = ENABLE -[AIRDRAG] +[AIR_DRAG] // Enable only when the center object is defined as the Earth calculation = ENABLE logging = ENABLE @@ -23,7 +23,7 @@ molecular_temperature_degC = 3 // Atmosphere Temperature[degC] molecular_weight = 18.0 // Molecular weight of the thermosphere[g/mol] -[SRDIST] +[SOLAR_RADIATION_PRESSURE] calculation = ENABLE logging = ENABLE diff --git a/src/Disturbance/InitDisturbance.cpp b/src/Disturbance/InitDisturbance.cpp index 22429b515..a807fdfee 100644 --- a/src/Disturbance/InitDisturbance.cpp +++ b/src/Disturbance/InitDisturbance.cpp @@ -13,7 +13,7 @@ AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b) { auto conf = IniAccess(ini_path); - const char* section = "AIRDRAG"; + const char* section = "AIR_DRAG"; double t_w = conf.ReadDouble(section, "wall_temperature_degC") + 273.0; double t_m = conf.ReadDouble(section, "molecular_temperature_degC") + 273.0; @@ -31,7 +31,7 @@ AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, SolarRadiation InitSRDist(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b) { auto conf = IniAccess(ini_path); - const char* section = "SRDIST"; + const char* section = "SOLAR_RADIATION_PRESSURE"; bool calcen = conf.ReadEnable(section, CALC_LABEL); bool logen = conf.ReadEnable(section, LOG_LABEL); @@ -67,7 +67,7 @@ GravityGradient InitGravityGradient(std::string ini_path, const double mu_m3_s2) MagDisturbance InitMagDisturbance(std::string ini_path, const RMMParams& rmm_params) { auto conf = IniAccess(ini_path); - const char* section = "MAG_DISTURBANCE"; + const char* section = "MAGNETIC_DISTURBANCE"; MagDisturbance mag_dist(rmm_params); mag_dist.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); @@ -92,7 +92,7 @@ GeoPotential InitGeoPotential(std::string ini_path) { ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes) { // Generate a list of bodies to be calculated in "CelesInfo" auto conf_celes = IniAccess(ini_path_celes); - const char* section_celes = "CelestialInformation"; + const char* section_celes = "CELESTIAL_INFORMATION"; const int num_of_selected_body = conf_celes.ReadInt(section_celes, "number_of_selected_body"); std::string center_object = conf_celes.ReadString(section_celes, "center_object"); std::set selected_body_list; From ee498bb5162ada4c406a064018fdf0b4a3d3d568 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:22:54 +0100 Subject: [PATCH 0119/1086] Fix to use SNAKE_CASE for ground station --- data/sample/initialize_files/sample_ground_station.ini | 4 ++-- src/Simulation/GroundStation/GroundStation.cpp | 2 +- .../GroundStation/SampleGroundStation/SampleGSComponents.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/data/sample/initialize_files/sample_ground_station.ini b/data/sample/initialize_files/sample_ground_station.ini index 1fd645b73..e238f6220 100644 --- a/data/sample/initialize_files/sample_ground_station.ini +++ b/data/sample/initialize_files/sample_ground_station.ini @@ -1,4 +1,4 @@ -[GS0] +[GROUND_STATION_0] // Position of the ground station latitude_deg = 26.140837 longitude_deg = 127.661483 @@ -7,6 +7,6 @@ height_m = 3.4 // The minimum limit of elevation to work the station elevation_limit_angle_deg = 5.0 -[COMPONENTS_FILE] +[COMPONENT_FILES] ground_station_antenna_file = ../../data/sample/initialize_files/components/ground_station_antenna.ini ground_station_calculator_file = ../../data/sample/initialize_files/components/ground_station_calculator.ini diff --git a/src/Simulation/GroundStation/GroundStation.cpp b/src/Simulation/GroundStation/GroundStation.cpp index d51a9f188..b737345af 100644 --- a/src/Simulation/GroundStation/GroundStation.cpp +++ b/src/Simulation/GroundStation/GroundStation.cpp @@ -28,7 +28,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { std::string gs_ini_path = config->gs_file_; auto conf = IniAccess(gs_ini_path); - const char* section_base = "GS"; + const char* section_base = "GROUND_STATION_"; const std::string section_tmp = section_base + std::to_string(static_cast(gs_id)); const char* Section = section_tmp.data(); diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp b/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp index 832738d25..cd983d49f 100644 --- a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp +++ b/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp @@ -9,10 +9,10 @@ SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); - std::string ant_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ground_station_antenna_file"); + std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); config_->main_logger_->CopyFileToLogDir(ant_ini_path); antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); - std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ground_station_calculator_file"); + std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); config_->main_logger_->CopyFileToLogDir(gscalculator_ini_path); gs_calculator_ = new GScalculator(InitGScalculator(gscalculator_ini_path)); } From 8503afb792ff1bc44e371844b427bbc6acb3f7d3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:25:52 +0100 Subject: [PATCH 0120/1086] Fix to use SNAKE_CASE for local environment --- data/sample/initialize_files/sample_local_environment.ini | 4 ++-- src/Environment/Local/InitLocalEnvironment.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/sample_local_environment.ini b/data/sample/initialize_files/sample_local_environment.ini index 260eac7ee..1371d73c8 100644 --- a/data/sample/initialize_files/sample_local_environment.ini +++ b/data/sample/initialize_files/sample_local_environment.ini @@ -1,4 +1,4 @@ -[MAG_ENVIRONMENT] +[MAGNETIC_FIELD_ENVIRONMENT] calculation = ENABLE logging = ENABLE coefficient_file = ../../../s2e-core/src/Library/igrf/igrf13.coef @@ -7,7 +7,7 @@ magnetic_field_random_walk_limit_nT = 400.0 magnetic_field_white_noise_standard_deviation_nT = 50.0 -[SRP] +[SOLAR_RADIATION_PRESSURE_ENVIRONMENT] calculation = ENABLE logging = ENABLE diff --git a/src/Environment/Local/InitLocalEnvironment.cpp b/src/Environment/Local/InitLocalEnvironment.cpp index 9bb1d5bd2..7a1657271 100644 --- a/src/Environment/Local/InitLocalEnvironment.cpp +++ b/src/Environment/Local/InitLocalEnvironment.cpp @@ -14,7 +14,7 @@ MagEnvironment InitMagEnvironment(std::string ini_path) { auto conf = IniAccess(ini_path); - const char* section = "MAG_ENVIRONMENT"; + const char* section = "MAGNETIC_FIELD_ENVIRONMENT"; std::string fname = conf.ReadString(section, "coefficient_file"); double mag_rwdev = conf.ReadDouble(section, "magnetic_field_random_walk_speed_nT"); @@ -30,7 +30,7 @@ MagEnvironment InitMagEnvironment(std::string ini_path) { SRPEnvironment InitSRPEnvironment(std::string ini_path, LocalCelestialInformation* local_celes_info) { auto conf = IniAccess(ini_path); - const char* section = "SRP"; + const char* section = "SOLAR_RADIATION_PRESSURE_ENVIRONMENT"; SRPEnvironment srp_env(local_celes_info); srp_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); From 83b8cf6868ecd4290b5e4098fc4a84a8c8d7f65e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:27:31 +0100 Subject: [PATCH 0121/1086] Fix to use SNAKE_CASE for disturbance --- data/sample/initialize_files/sample_disturbance.ini | 2 +- src/Disturbance/InitDisturbance.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index bac0ddc21..2a46ae623 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -23,7 +23,7 @@ molecular_temperature_degC = 3 // Atmosphere Temperature[degC] molecular_weight = 18.0 // Molecular weight of the thermosphere[g/mol] -[SOLAR_RADIATION_PRESSURE] +[SOLAR_RADIATION_PRESSURE_DISTURBANCE] calculation = ENABLE logging = ENABLE diff --git a/src/Disturbance/InitDisturbance.cpp b/src/Disturbance/InitDisturbance.cpp index a807fdfee..ead9e58cf 100644 --- a/src/Disturbance/InitDisturbance.cpp +++ b/src/Disturbance/InitDisturbance.cpp @@ -31,7 +31,7 @@ AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, SolarRadiation InitSRDist(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b) { auto conf = IniAccess(ini_path); - const char* section = "SOLAR_RADIATION_PRESSURE"; + const char* section = "SOLAR_RADIATION_PRESSURE_DISTURBANCE"; bool calcen = conf.ReadEnable(section, CALC_LABEL); bool logen = conf.ReadEnable(section, LOG_LABEL); From 61dba94dba3633a16feb3e703e2c54cc13b01ad6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:43:41 +0100 Subject: [PATCH 0122/1086] Fix to use SNAKE_CASE for spacecraft --- .../initialize_files/sample_satellite.ini | 15 ++++--------- src/Disturbance/Disturbances.cpp | 2 +- src/Dynamics/Attitude/InitAttitude.cpp | 2 +- src/Dynamics/Thermal/InitTemperature.cpp | 6 ++--- src/Environment/Local/LocalEnvironment.cpp | 2 +- .../SampleSpacecraft/SampleComponents.cpp | 22 +++++++++---------- .../Spacecraft/Structure/Structure.cpp | 2 +- 7 files changed, 22 insertions(+), 29 deletions(-) diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index f0879c1b4..af6657a46 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -22,7 +22,7 @@ initial_torque_b_Nm(0) = +0.000 initial_torque_b_Nm(1) = -0.000 initial_torque_b_Nm(2) = 0.000 -[ControlledAttitude] +[CONTROLLED_ATTITUDE] // Mode definitions // INERTIAL_STABILIZE // SUN_POINTING @@ -117,24 +117,17 @@ error_tolerance = 0.0001 /////////////////////////////////////////////////////////////////////////////// -[Thermal] +[THERMAL] calculation = DISABLE debug = 0 thermal_file_directory = ../../data/sample/initialize_files/thermal_csv_files/ -[LOCAL_ENVIRONMENT] +[SETTING_FILES] local_environment_file = ../../data/sample/initialize_files/sample_local_environment.ini - - -[DISTURBANCE] disturbance_file = ../../data/sample/initialize_files/sample_disturbance.ini - - -[STRUCTURE_FILE] structure_file = ../../data/sample/initialize_files/sample_structure.ini - -[COMPONENTS_FILE] +[COMPONENT_FILES] gyro_file = ../../data/sample/initialize_files/components/gyro_sensor.ini magetometer_file = ../../data/sample/initialize_files/components/magnetometer.ini stt_file = ../../data/sample/initialize_files/components/star_sensor.ini diff --git a/src/Disturbance/Disturbances.cpp b/src/Disturbance/Disturbances.cpp index 6ca48fb6b..6e9a72b9b 100644 --- a/src/Disturbance/Disturbances.cpp +++ b/src/Disturbance/Disturbances.cpp @@ -71,7 +71,7 @@ Vector<3> Disturbances::GetAccelerationI() { return sum_acceleration_i_; } void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); - ini_fname_ = iniAccess.ReadString("DISTURBANCE", "disturbance_file"); + ini_fname_ = iniAccess.ReadString("SETTING_FILES", "disturbance_file"); GravityGradient* gg_dist = new GravityGradient(InitGravityGradient(ini_fname_, glo_env->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); disturbances_.push_back(gg_dist); diff --git a/src/Dynamics/Attitude/InitAttitude.cpp b/src/Dynamics/Attitude/InitAttitude.cpp index e0a00ae28..30d04dff6 100644 --- a/src/Dynamics/Attitude/InitAttitude.cpp +++ b/src/Dynamics/Attitude/InitAttitude.cpp @@ -28,7 +28,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel } else if (propagate_mode == "CONTROLLED") { // Controlled attitude IniAccess ini_file_ca(file_name); - const char* section_ca_ = "ControlledAttitude"; + const char* section_ca_ = "CONTROLLED_ATTITUDE"; const std::string main_mode_in = ini_file.ReadString(section_ca_, "main_mode"); const std::string sub_mode_in = ini_file.ReadString(section_ca_, "sub_mode"); diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index f6cf45257..e964cdc44 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -53,7 +53,7 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st vector> vnodestr; // string vector of node property data int nodes_num = 1; - bool is_calc_enabled = mainIni.ReadEnable("Thermal", "calculation"); + bool is_calc_enabled = mainIni.ReadEnable("THERMAL", "calculation"); if (is_calc_enabled == false) { // Return here to avoid CSV file reading Temperature* temperature; @@ -62,8 +62,8 @@ Temperature* InitTemperature(const std::string ini_path, const double rk_prop_st } // read ini-file settings - string file_path = mainIni.ReadString("Thermal", "thermal_file_directory"); - bool debug = mainIni.ReadBoolean("Thermal", "debug"); + string file_path = mainIni.ReadString("THERMAL", "thermal_file_directory"); + bool debug = mainIni.ReadBoolean("THERMAL", "debug"); // Read Node Properties from CSV File string filepath_node = file_path + "node.csv"; diff --git a/src/Environment/Local/LocalEnvironment.cpp b/src/Environment/Local/LocalEnvironment.cpp index 3a3edfff8..785d1255d 100644 --- a/src/Environment/Local/LocalEnvironment.cpp +++ b/src/Environment/Local/LocalEnvironment.cpp @@ -24,7 +24,7 @@ LocalEnvironment::~LocalEnvironment() { void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { // Read file name IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); - std::string ini_fname = iniAccess.ReadString("LOCAL_ENVIRONMENT", "local_environment_file"); + std::string ini_fname = iniAccess.ReadString("SETTING_FILES", "local_environment_file"); // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp index 5250e2fc5..c4ea6dc21 100644 --- a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp +++ b/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp @@ -25,61 +25,61 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur hils_port_manager_ = new HilsPortManager(); // Gyro - std::string ini_path = iniAccess.ReadString("COMPONENTS_FILE", "gyro_file"); + std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); config_->main_logger_->CopyFileToLogDir(ini_path); gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), dynamics_)); // MagSensor - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "magetometer_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_sensor_ = new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); // STT - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "stt_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDir(ini_path); stt_ = new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), dynamics_, local_env_)); // SunSensor - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "ss_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); config_->main_logger_->CopyFileToLogDir(ini_path); sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_env_->GetSrp()), &(local_env_->GetCelesInfo()))); // GNSS-R - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "gnss_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); config_->main_logger_->CopyFileToLogDir(ini_path); gnss_ = new GNSSReceiver( InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimTime()))); // MagTorquer - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "magetorquer_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_torquer_ = new MagTorquer( InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); // RW - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "rw_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); config_->main_logger_->CopyFileToLogDir(ini_path); rw_ = new RWModel( InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), glo_env_->GetSimTime().GetCompoStepSec())); // Torque Generator - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "torque_generator_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); config_->main_logger_->CopyFileToLogDir(ini_path); torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_gen, ini_path, dynamics_)); // Thruster - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "thruster_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "thruster_file"); config_->main_logger_->CopyFileToLogDir(ini_path); thruster_ = new SimpleThruster(InitSimpleThruster(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, structure_, dynamics)); // Force Generator - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "force_generator_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "force_generator_file"); config_->main_logger_->CopyFileToLogDir(ini_path); force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_gen, ini_path, dynamics_)); // Antenna - ini_path = iniAccess.ReadString("COMPONENTS_FILE", "antenna_file"); + ini_path = iniAccess.ReadString("COMPONENT_FILES", "antenna_file"); config_->main_logger_->CopyFileToLogDir(ini_path); antenna_ = new Antenna(InitAntenna(1, ini_path)); diff --git a/src/Simulation/Spacecraft/Structure/Structure.cpp b/src/Simulation/Spacecraft/Structure/Structure.cpp index 3d142d6aa..003352481 100644 --- a/src/Simulation/Spacecraft/Structure/Structure.cpp +++ b/src/Simulation/Spacecraft/Structure/Structure.cpp @@ -19,7 +19,7 @@ Structure::~Structure() { void Structure::Initialize(SimulationConfig* sim_config, const int sat_id) { // Read file name IniAccess conf = IniAccess(sim_config->sat_file_[sat_id]); - std::string ini_fname = conf.ReadString("STRUCTURE_FILE", "structure_file"); + std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize From e3da8a2cfea26464ddc82fe199b2553e49bf01c9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:49:38 +0100 Subject: [PATCH 0123/1086] Fix to use SNAKE_CASE for structure --- data/sample/initialize_files/sample_structure.ini | 4 ++-- src/Simulation/Spacecraft/Structure/InitStructure.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/sample_structure.ini b/data/sample/initialize_files/sample_structure.ini index 11722eb8f..898997f29 100644 --- a/data/sample/initialize_files/sample_structure.ini +++ b/data/sample/initialize_files/sample_structure.ini @@ -5,7 +5,7 @@ // If users want to define the origin as a specific point, they need to set all vectors to suit their definition carefully. // -[STRUCTURE] +[KINEMATIC_PARAMETERS] // Inertia Tensor @ body fixed frame [kg・m2] inertia_tensor_kgm2(0) = 0.1 // I_xx inertia_tensor_kgm2(1) = 0.0 // I_xy @@ -99,7 +99,7 @@ air_specularity_3 = 0.4 air_specularity_4 = 0.4 air_specularity_5 = 0.4 -[RMM] +[RESIDUAL_MAGNETIC_MOMENT] // Constant component of Residual Magnetic Moment(RMM) [A・m^2] rmm_constant_b_Am2(0) = 0.04 rmm_constant_b_Am2(1) = 0.04 diff --git a/src/Simulation/Spacecraft/Structure/InitStructure.cpp b/src/Simulation/Spacecraft/Structure/InitStructure.cpp index 77d348653..2bec77179 100644 --- a/src/Simulation/Spacecraft/Structure/InitStructure.cpp +++ b/src/Simulation/Spacecraft/Structure/InitStructure.cpp @@ -12,7 +12,7 @@ #define MIN_VAL 1e-6 KinematicsParams InitKinematicsParams(std::string ini_path) { auto conf = IniAccess(ini_path); - const char* section = "STRUCTURE"; + const char* section = "KINEMATIC_PARAMETERS"; Vector<3> cg_b; conf.ReadVector(section, "center_of_gravity_b_m", cg_b); @@ -109,7 +109,7 @@ vector InitSurfaces(std::string ini_path) { RMMParams InitRMMParams(std::string ini_path) { auto conf = IniAccess(ini_path); - const char* section = "RMM"; + const char* section = "RESIDUAL_MAGNETIC_MOMENT"; Vector<3> rmm_const_b; conf.ReadVector(section, "rmm_constant_b_Am2", rmm_const_b); From d94004a36c440a4dee738c24046afd712171f06f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:51:08 +0100 Subject: [PATCH 0124/1086] Fix to use SNAKE_CASE for battery --- data/sample/initialize_files/components/battery.ini | 4 ++-- src/Component/Power/InitBat.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/components/battery.ini b/data/sample/initialize_files/components/battery.ini index 011bd173d..868c115bd 100644 --- a/data/sample/initialize_files/components/battery.ini +++ b/data/sample/initialize_files/components/battery.ini @@ -1,4 +1,4 @@ -[BAT1] +[BATTERY_1] prescaler = 10 // Number of series of the battery module @@ -31,4 +31,4 @@ constant_charge_current_rate_C = 0.2 constant_voltage_charge_voltage_V = 12.3 // Battery internal registance + wire/connector resistance between BAT and PCU [Ohm] -battery_resistance_Ohm = 0.4 \ No newline at end of file +battery_resistance_Ohm = 0.4 diff --git a/src/Component/Power/InitBat.cpp b/src/Component/Power/InitBat.cpp index b310acaf1..1ff27402b 100644 --- a/src/Component/Power/InitBat.cpp +++ b/src/Component/Power/InitBat.cpp @@ -16,7 +16,7 @@ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, doub const std::string st_bat_id = std::to_string(bat_id); const char* cs = st_bat_id.data(); - char Section[30] = "BAT"; + char Section[30] = "BATTERY_"; strcat(Section, cs); int prescaler = bat_conf.ReadInt(Section, "prescaler"); From 1d60427aed8fe0881548fba4aebfd280e88b989a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:52:07 +0100 Subject: [PATCH 0125/1086] Fix to use SNAKE_CASE for force generator --- data/sample/initialize_files/components/force_generator.ini | 4 ++-- src/Component/IdealComponents/InitializeForceGenerator.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/force_generator.ini b/data/sample/initialize_files/components/force_generator.ini index f942e9d7b..1a470c0a5 100644 --- a/data/sample/initialize_files/components/force_generator.ini +++ b/data/sample/initialize_files/components/force_generator.ini @@ -1,10 +1,10 @@ -[ForceGenerator] +[FORCE_GENERATOR] // Standard deviation of force magnitude error [N] force_magnitude_standard_deviation_N = 0.01 // Standard deviation of force direction error [deg] force_direction_standard_deviation_deg = 1 -[ComponentBase] +[COMPONENT_BASE] // Prescaler with respect to the component update period prescaler = 1 diff --git a/src/Component/IdealComponents/InitializeForceGenerator.cpp b/src/Component/IdealComponents/InitializeForceGenerator.cpp index 6972c1040..e7acb3d13 100644 --- a/src/Component/IdealComponents/InitializeForceGenerator.cpp +++ b/src/Component/IdealComponents/InitializeForceGenerator.cpp @@ -11,11 +11,11 @@ ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::st IniAccess ini_file(file_name); // CompoBase - int prescaler = ini_file.ReadInt("ComponentBase", "prescaler"); + int prescaler = ini_file.ReadInt("COMPONENT_BASE", "prescaler"); if (prescaler <= 1) prescaler = 1; // ForceGenerator - char section[30] = "ForceGenerator"; + char section[30] = "FORCE_GENERATOR"; double force_magnitude_standard_deviation_N = ini_file.ReadDouble(section, "force_magnitude_standard_deviation_N"); double force_direction_standard_deviation_deg = ini_file.ReadDouble(section, "force_direction_standard_deviation_deg"); double force_direction_standard_deviation_rad = libra::deg_to_rad * force_direction_standard_deviation_deg; From 8a1a564eefcdc4da4431f8be4874f652fc727fb4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 12:52:49 +0100 Subject: [PATCH 0126/1086] Fix to use SNAKE_CASE for gnss receiver --- data/sample/initialize_files/components/gnss_receiver.ini | 2 +- src/Component/AOCS/InitGnssReceiver.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/components/gnss_receiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini index ae53e651c..b9ff2d946 100644 --- a/data/sample/initialize_files/components/gnss_receiver.ini +++ b/data/sample/initialize_files/components/gnss_receiver.ini @@ -1,4 +1,4 @@ -[GNSSReceiver] +[GNSS_RECEIVER] prescaler = 10 // Position of antenna at body frame [m] diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index def44c130..ff916653b 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -23,7 +23,7 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli GNSSReceiverParam gnssreceiver_param; IniAccess gnssr_conf(fname); - char GSection[30] = "GNSSReceiver"; + char GSection[30] = "GNSS_RECEIVER"; int prescaler = gnssr_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; From e7baee3cbfaa59c09396830ba70d032efb3f405d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:26:45 +0100 Subject: [PATCH 0127/1086] Fix to use SNAKE_CASE for antenna --- .../initialize_files/components/ground_station_antenna.ini | 4 +--- .../sample/initialize_files/components/spacecraft_antenna.ini | 4 +--- src/Component/CommGS/InitAntenna.cpp | 2 +- 3 files changed, 3 insertions(+), 7 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index 5f4c7c623..86ed52238 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -1,6 +1,4 @@ -[ANT1] -// Example of antenna on ground station - +[ANTENNA_1] // Quaternion converts body-fixed frame to component frame quaternion_b2c(0) = 0 quaternion_b2c(1) = 0 diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 602455659..6fdfac644 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -1,6 +1,4 @@ -[ANT1] -// Example of antenna on spacecraft - +[ANTENNA_1] // Quaternion converts body-fixed frame to component frame quaternion_b2c(0) = 0 quaternion_b2c(1) = 0 diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/Component/CommGS/InitAntenna.cpp index 09f87fcd3..889b58172 100644 --- a/src/Component/CommGS/InitAntenna.cpp +++ b/src/Component/CommGS/InitAntenna.cpp @@ -20,7 +20,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { const std::string st_ant_id = std::to_string(static_cast(antenna_id)); const char *cs = st_ant_id.data(); - char Section[30] = "ANT"; + char Section[30] = "ANTENNA_"; strcat(Section, cs); Quaternion q_b2c; From 4ca2b9d4b76152bc20c6ecb68fe9df2518ef20ea Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:28:09 +0100 Subject: [PATCH 0128/1086] Fix to use SNAKE_CASE for ground station calculator --- .../components/ground_station_calculator.ini | 2 +- src/Component/CommGS/InitGsCalculator.cpp | 6 +----- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_calculator.ini b/data/sample/initialize_files/components/ground_station_calculator.ini index ff280adcf..9dbeedfcd 100644 --- a/data/sample/initialize_files/components/ground_station_calculator.ini +++ b/data/sample/initialize_files/components/ground_station_calculator.ini @@ -1,4 +1,4 @@ -[GScalculator] +[GROUND_STATION_CALCULATOR] // Polarization loss [dB] loss_polarization_dB = 0.0 diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/Component/CommGS/InitGsCalculator.cpp index 87583fc1a..8b741aad3 100644 --- a/src/Component/CommGS/InitGsCalculator.cpp +++ b/src/Component/CommGS/InitGsCalculator.cpp @@ -13,11 +13,7 @@ GScalculator InitGScalculator(const std::string fname) { IniAccess gs_conf(fname); - // const string st_gs_id = std::to_string(static_cast(gs_id)); - // const char *cs = st_gs_id.data(); - - char Section[30] = "GScalculator"; - // strcat(Section, cs); + char Section[30] = "GROUND_STATION_CALCULATOR"; double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization_dB"); double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere_dB"); From 682e47ab87376bd8b1c8170da283142d267ffbe5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:38:52 +0100 Subject: [PATCH 0129/1086] Fix to use SNAKE_CASE for gyro and magnetometer --- data/sample/initialize_files/components/gyro_sensor.ini | 6 +++--- data/sample/initialize_files/components/magnetometer.ini | 6 +++--- src/Component/AOCS/InitGyro.cpp | 8 ++++---- src/Component/AOCS/InitMagSensor.cpp | 8 ++++---- src/Component/Abstract/InitializeSensorBase_tfs.hpp | 2 +- src/Interface/SpacecraftInOut/Ports/PowerPort.cpp | 2 +- 6 files changed, 16 insertions(+), 16 deletions(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index 7838194a0..41b423bf7 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -1,4 +1,4 @@ -[GYRO] +[GYRO_SENSOR] prescaler = 10 // Quaternion from body frame to component frame @@ -8,7 +8,7 @@ quaternion_b2c(1) = 0.0 quaternion_b2c(2) = 0.0 quaternion_b2c(3) = 1.0 -[SensorBaseGyro] +[SENSOR_BASE_GYRO_SENSOR] // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), scale_factor_c(0) = 1.0 @@ -45,6 +45,6 @@ random_walk_standard_deviation_c_rad_s(2) = 1e-3 range_to_constant_rad_s = 5.0 // smaller than Range_to_zero range_to_zero_rad_s = 10.0 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/data/sample/initialize_files/components/magnetometer.ini b/data/sample/initialize_files/components/magnetometer.ini index 70a493295..6561e41f6 100644 --- a/data/sample/initialize_files/components/magnetometer.ini +++ b/data/sample/initialize_files/components/magnetometer.ini @@ -1,4 +1,4 @@ -[MAGSENSOR] +[MAGNETOMETER] prescaler = 10 //Quaternion from body frame to component frame @@ -7,7 +7,7 @@ quaternion_b2c(1) = 0.0 quaternion_b2c(2) = 0.0 quaternion_b2c(3) = 1.0 -[SensorBaseMagnetometer] +[SENSOR_BASE_MAGNETOMETER] // Sensor Base // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), @@ -45,6 +45,6 @@ normal_random_standard_deviation_c_nT(2) = 10.0 range_to_constant_nT = 1.0e6 // smaller than Range_to_zero range_to_zero_nT = 1.5e6 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 62b1da861..4fb96486f 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -10,7 +10,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); - char GSection[30] = "GYRO"; + char GSection[30] = "GYRO_SENSOR"; Quaternion q_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); @@ -18,7 +18,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, if (prescaler <= 1) prescaler = 1; // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); Gyro gyro(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, dynamics); @@ -28,7 +28,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); - char GSection[30] = "GYRO"; + char GSection[30] = "GYRO_SENSOR"; Quaternion q_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); @@ -36,7 +36,7 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c if (prescaler <= 1) prescaler = 1; // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Gyro", "rad_s"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); // PowerPort power_port->InitializeWithInitializeFile(fname); diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index 7bb8d5059..05adb2465 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -9,7 +9,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); - char MSSection[30] = "MAGSENSOR"; + char MSSection[30] = "MAGNETOMETER"; int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -18,7 +18,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Magnetometer", "nT"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); MagSensor magsensor(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, magnet); return magsensor; @@ -27,7 +27,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); - char MSSection[30] = "MAGSENSOR"; + char MSSection[30] = "MAGNETOMETER"; int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -36,7 +36,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), "Magnetometer", "nT"); + SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); // PowerPort power_port->InitializeWithInitializeFile(fname); diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index 72e6bff29..9e7057892 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -10,7 +10,7 @@ template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit) { IniAccess ini_file(file_name); - std::string section = "SensorBase" + component_name; + std::string section = "SENSOR_BASE_" + component_name; libra::Vector scale_factor_vector; ini_file.ReadVector(section.c_str(), "scale_factor_c", scale_factor_vector); diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp index 732cb28f5..4f1c37f78 100644 --- a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -63,7 +63,7 @@ void PowerPort::SubtractAssumedPowerConsumption(const double power) { void PowerPort::InitializeWithInitializeFile(const std::string file_name) { IniAccess initialize_file(file_name); - const std::string section_name = "PowerPort"; + const std::string section_name = "POWER_PORT"; double minimum_voltage = initialize_file.ReadDouble(section_name.c_str(), "minimum_voltage_V"); this->SetMinimumVoltage(minimum_voltage); From 6f44ab3505a8a766aa0bc959f90db46507e5760e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:41:06 +0100 Subject: [PATCH 0130/1086] Fix to use SNAKE_CASE for magnetorquer --- data/sample/initialize_files/components/magnetorquer.ini | 4 ++-- src/Component/AOCS/InitMagTorquer.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/magnetorquer.ini b/data/sample/initialize_files/components/magnetorquer.ini index 53a511343..42eabadbc 100644 --- a/data/sample/initialize_files/components/magnetorquer.ini +++ b/data/sample/initialize_files/components/magnetorquer.ini @@ -1,4 +1,4 @@ -[MAGTORQUER] +[MAGNETORQUER] prescaler = 10 //Quaternion from body frame to component frame @@ -49,6 +49,6 @@ white_noise_standard_deviation_c_Am2(0) = 0.0 white_noise_standard_deviation_c_Am2(1) = 0.0 white_noise_standard_deviation_c_Am2(2) = 0.0 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index 928a4dd04..b404403bc 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -9,7 +9,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { IniAccess magtorquer_conf(fname); - char MTSection[30] = "MAGTORQUER"; + char MTSection[30] = "MAGNETORQUER"; int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -51,7 +51,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { IniAccess magtorquer_conf(fname); - char MTSection[30] = "MAGTORQUER"; + char MTSection[30] = "MAGNETORQUER"; int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; From 7195e09685db84565260e03d6f88907d222ce00f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:41:53 +0100 Subject: [PATCH 0131/1086] Fix to use SNAKE_CASE for PCU --- data/sample/initialize_files/components/pcu_initial_study.ini | 4 ++-- src/Component/Power/InitPcu_InitialStudy.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/components/pcu_initial_study.ini b/data/sample/initialize_files/components/pcu_initial_study.ini index ad8991511..74140d813 100644 --- a/data/sample/initialize_files/components/pcu_initial_study.ini +++ b/data/sample/initialize_files/components/pcu_initial_study.ini @@ -1,2 +1,2 @@ -[PCU1] -prescaler = 10 \ No newline at end of file +[PCU_INITIAL_STUDY1] +prescaler = 10 diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/Component/Power/InitPcu_InitialStudy.cpp index 4df1a84ae..2b30950d4 100644 --- a/src/Component/Power/InitPcu_InitialStudy.cpp +++ b/src/Component/Power/InitPcu_InitialStudy.cpp @@ -18,7 +18,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, con const std::string st_pcu_id = std::to_string(pcu_id); const char* cs = st_pcu_id.data(); - char Section[30] = "PCU"; + char Section[30] = "PCU_INITIAL_STUDY"; strcat(Section, cs); int prescaler = pcu_conf.ReadInt(Section, "prescaler"); From 6489cdd74e3a47f3efa7c2567ad880386db73968 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:44:12 +0100 Subject: [PATCH 0132/1086] Fix to use SNAKE_CASE for reaction wheel --- data/sample/initialize_files/components/reaction_wheel.ini | 4 ++-- src/Component/AOCS/InitRwModel.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/components/reaction_wheel.ini b/data/sample/initialize_files/components/reaction_wheel.ini index 40ac4f460..36b2e04d3 100644 --- a/data/sample/initialize_files/components/reaction_wheel.ini +++ b/data/sample/initialize_files/components/reaction_wheel.ini @@ -1,4 +1,4 @@ -[RW1] +[REACTION_WHEEL_1] // prescaler defines update period of thie component // update period = prescaler * step sec prescaler = 1 @@ -60,6 +60,6 @@ structural_resonance_frequency_Hz = 585.0 //[Hz] damping_factor = 0.1 //[ ] bandwidth = 0.001 //[ ] -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index 4093c67f4..2298f727d 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -40,7 +40,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double IniAccess rwmodel_conf(file_name); const std::string st_actuator_num = std::to_string(static_cast(actuator_id)); const char* cs = st_actuator_num.data(); - std::string section_tmp = "RW"; + std::string section_tmp = "REACTION_WHEEL_"; section_tmp += cs; const char* RWsection = section_tmp.data(); From 972d8718009dd79bed205b5e57b7ca0b308a85f5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:45:40 +0100 Subject: [PATCH 0133/1086] Fix to use SNAKE_CASE for SAP --- .../initialize_files/components/solar_array_panel.ini | 6 +++--- src/Component/Power/InitPcu_InitialStudy.cpp | 2 +- src/Component/Power/InitSap.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/solar_array_panel.ini b/data/sample/initialize_files/components/solar_array_panel.ini index eaccdebc6..214c5e982 100644 --- a/data/sample/initialize_files/components/solar_array_panel.ini +++ b/data/sample/initialize_files/components/solar_array_panel.ini @@ -1,4 +1,4 @@ -[SAP1] +[SOLAR_ARRAY_PANEL_1] prescaler = 10 // Area of a solar cell [m2] @@ -22,7 +22,7 @@ number_of_series = 7 number_of_parallel = 6 -[SAP2] +[SOLAR_ARRAY_PANEL_2] prescaler = 10 // Area of a solar cell [m2] @@ -46,7 +46,7 @@ number_of_series = 7 number_of_parallel = 1 -[SAP3] +[SOLAR_ARRAY_PANEL_3] prescaler = 10 // Area of a solar cell [m2] diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/Component/Power/InitPcu_InitialStudy.cpp index 2b30950d4..f8fc17a4a 100644 --- a/src/Component/Power/InitPcu_InitialStudy.cpp +++ b/src/Component/Power/InitPcu_InitialStudy.cpp @@ -18,7 +18,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, con const std::string st_pcu_id = std::to_string(pcu_id); const char* cs = st_pcu_id.data(); - char Section[30] = "PCU_INITIAL_STUDY"; + char Section[30] = "PCU_INITIAL_STUDY_"; strcat(Section, cs); int prescaler = pcu_conf.ReadInt(Section, "prescaler"); diff --git a/src/Component/Power/InitSap.cpp b/src/Component/Power/InitSap.cpp index 5dd8be6e0..6bdb6fd6e 100644 --- a/src/Component/Power/InitSap.cpp +++ b/src/Component/Power/InitSap.cpp @@ -16,7 +16,7 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons const std::string st_sap_id = std::to_string(sap_id); const char* cs = st_sap_id.data(); - char Section[30] = "SAP"; + char Section[30] = "SOLAR_ARRAY_PANEL_"; strcat(Section, cs); int prescaler = sap_conf.ReadInt(Section, "prescaler"); @@ -52,7 +52,7 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons const std::string st_sap_id = std::to_string(sap_id); const char* cs = st_sap_id.data(); - char Section[30] = "SAP"; + char Section[30] = "SOLAR_ARRAY_PANEL_"; strcat(Section, cs); int prescaler = sap_conf.ReadInt(Section, "prescaler"); From d6cfb2435dc4a44ca39bb0c681124d4618f4f7b2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:47:56 +0100 Subject: [PATCH 0134/1086] Fix to use SNAKE_CASE for STT --- data/sample/initialize_files/components/star_sensor.ini | 4 ++-- src/Component/AOCS/InitStt.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/star_sensor.ini b/data/sample/initialize_files/components/star_sensor.ini index c555a4684..3b9c70159 100644 --- a/data/sample/initialize_files/components/star_sensor.ini +++ b/data/sample/initialize_files/components/star_sensor.ini @@ -1,4 +1,4 @@ -[STT] +[STAR_SENSOR] prescaler = 10; // Quaternion from body frame to component frame @@ -32,6 +32,6 @@ moon_exclusion_angle_deg = 10 // Limit angular rate to capture stars[deg/s] angular_rate_limit_deg_s = 10.0 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 // V assumed_power_consumption_W = 1.0 //W diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index e77fe7139..d4c3b9323 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -13,7 +13,7 @@ using namespace std; STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); - string section_tmp = "STT"; + string section_tmp = "STAR_SENSOR"; const char* STTSection = section_tmp.data(); int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); @@ -44,7 +44,7 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); - string section_tmp = "STT"; + string section_tmp = "STAR_SENSOR"; const char* STTSection = section_tmp.data(); int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); From 01b534e52c4ef5c979e455c4fe8400b5485ae2ea Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:49:46 +0100 Subject: [PATCH 0135/1086] Fix to use SNAKE_CASE for sun sensor --- data/sample/initialize_files/components/sun_sensor.ini | 4 ++-- src/Component/AOCS/InitSunSensor.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/sun_sensor.ini b/data/sample/initialize_files/components/sun_sensor.ini index c6235e66f..e04cda344 100644 --- a/data/sample/initialize_files/components/sun_sensor.ini +++ b/data/sample/initialize_files/components/sun_sensor.ini @@ -1,4 +1,4 @@ -[SUNSENSOR1] +[SUN_SENSOR_1] prescaler = 10; // Quaternion from body frame to component frame @@ -22,6 +22,6 @@ bias_standard_deviation_deg = 0.5 // If it becomes smaller than this, it becomes impossible to get the sun direction intensity_lower_threshold_percent = 30.0 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index c7417891b..c8a750b21 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -13,7 +13,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); - const char* sensor_name = "SUNSENSOR"; + const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); const char* Section = section_tmp.c_str(); @@ -46,7 +46,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); - const char* sensor_name = "SUNSENSOR"; + const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); const char* Section = section_tmp.c_str(); From e40f9d03261d85a379ab52608232ea283127e037 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:50:34 +0100 Subject: [PATCH 0136/1086] Fix to use SNAKE_CASE for telescope --- src/Component/Mission/Telescope/InitTelescope.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index 6a7b0eba1..0d3838ffb 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -21,7 +21,7 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string f const string st_sensor_id = std::to_string(static_cast(sensor_id)); const char* cs = st_sensor_id.data(); - char TelescopeSection[30] = "Telescope"; + char TelescopeSection[30] = "TELESCOPE_"; #ifdef WIN32 strcat_s(TelescopeSection, cs); #else From 4ea4a45500f0fd10350bfb881379a25a34d74e76 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:50:43 +0100 Subject: [PATCH 0137/1086] Fix to use SNAKE_CASE for telescope --- data/sample/initialize_files/components/telescope.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/telescope.ini b/data/sample/initialize_files/components/telescope.ini index 28bf4908a..3c0a974c3 100644 --- a/data/sample/initialize_files/components/telescope.ini +++ b/data/sample/initialize_files/components/telescope.ini @@ -1,4 +1,4 @@ -[Telescope1] +[TELESCOPE_1] // Frame conversion quaternion from body-fixed frame to component frame // +X axis of the component frame: Line of sight direction // +Y axis of the component frame: +Y axis of the image sensor From 52cabb5c193243a6c9a1aa0efb057ba3817f24b9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:51:49 +0100 Subject: [PATCH 0138/1086] Fix to use SNAKE_CASE for thermal compo --- data/sample/initialize_files/components/thermal_components.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/thermal_components.ini b/data/sample/initialize_files/components/thermal_components.ini index df1776fb3..bb1c943ba 100644 --- a/data/sample/initialize_files/components/thermal_components.ini +++ b/data/sample/initialize_files/components/thermal_components.ini @@ -1,4 +1,4 @@ -[ThermoCompo1] +[THERMAL_COMPONENT_1] is_debug = 0 is_zeus_correct_enabled = 1 file_path = data/ini/thermal_csv_files/ \ No newline at end of file From d16ebfdc63b05fbe6399ece9b304c063a84df6fd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:53:56 +0100 Subject: [PATCH 0139/1086] Fix to use SNAKE_CASE for thruster --- data/sample/initialize_files/components/thruster.ini | 4 ++-- src/Component/Propulsion/InitSimpleThruster.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/thruster.ini b/data/sample/initialize_files/components/thruster.ini index efc365431..fd34d536f 100644 --- a/data/sample/initialize_files/components/thruster.ini +++ b/data/sample/initialize_files/components/thruster.ini @@ -1,4 +1,4 @@ -[Thruster1] +[THRUSTER_1] prescaler = 10; // Position of thruster head at body frame [m] @@ -20,6 +20,6 @@ thrust_error_standard_deviation_N = 0.001 // Standard deviation of thrust direction error [deg] direction_error_standard_deviation_deg = 1 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 412955032..84fe9d3dd 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -11,7 +11,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { IniAccess thruster_conf(fname); - std::string sectionstr = "THRUSTER" + std::to_string(thruster_id); + std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); auto* Section = sectionstr.c_str(); int prescaler = thruster_conf.ReadInt(Section, "prescaler"); @@ -38,7 +38,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { IniAccess thruster_conf(fname); - std::string sectionstr = "THRUSTER" + std::to_string(thruster_id); + std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); auto* Section = sectionstr.c_str(); int prescaler = thruster_conf.ReadInt(Section, "prescaler"); From ad089735dc49da5e0c622229fc233ac556d4bbcf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:56:06 +0100 Subject: [PATCH 0140/1086] Fix to use SNAKE_CASE for torque generator --- data/sample/initialize_files/components/torque_generator.ini | 4 ++-- src/Component/IdealComponents/InitializeTorqueGenerator.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/torque_generator.ini b/data/sample/initialize_files/components/torque_generator.ini index faf9f11b0..208b86354 100644 --- a/data/sample/initialize_files/components/torque_generator.ini +++ b/data/sample/initialize_files/components/torque_generator.ini @@ -1,10 +1,10 @@ -[TorqueGenerator] +[TORQUE_GENERATOR] // Standard deviation of torque magnitude error [Nm] torque_magnitude_standard_deviation_Nm = 0.01 // Standard deviation of torque direction error [deg] torque_direction_standard_deviation_deg = 1 -[ComponentBase] +[COMPONENT_BASE] // Prescaler with respect to the component update period prescaler = 1 diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp index 73a4431c7..a64745eb1 100644 --- a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp +++ b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp @@ -11,11 +11,11 @@ TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std:: IniAccess ini_file(file_name); // CompoBase - int prescaler = ini_file.ReadInt("ComponentBase", "prescaler"); + int prescaler = ini_file.ReadInt("COMPONENT_BASE", "prescaler"); if (prescaler <= 1) prescaler = 1; // TorqueGenerator - char section[30] = "TorqueGenerator"; + char section[30] = "TORQUE_GENERATOR"; double torque_magnitude_standard_deviation_Nm = ini_file.ReadDouble(section, "torque_magnitude_standard_deviation_Nm"); double torque_direction_standard_deviation_deg = ini_file.ReadDouble(section, "torque_direction_standard_deviation_deg"); double torque_direction_standard_deviation_rad = libra::deg_to_rad * torque_direction_standard_deviation_deg; From 7aeeaf314169291a70d4294edf34ad5e4cd5fd33 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 5 Feb 2023 20:57:33 +0100 Subject: [PATCH 0141/1086] Fix section name --- scripts/Plot/plot_gs_visibility.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index 2b74a2dd6..f79c0c65a 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -49,8 +49,8 @@ gs_ini_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + "/sample_ground_station.ini" configur = ConfigParser(comment_prefixes=('#', ';', '//'), inline_comment_prefixes=('#', ';', '//')) configur.read(gs_ini_file_name) -gs_lat_deg = configur.getfloat('GS0', 'latitude_deg') -gs_lon_deg = configur.getfloat('GS0', 'longitude_deg') +gs_lat_deg = configur.getfloat('GROUND_STATION_0', 'latitude_deg') +gs_lon_deg = configur.getfloat('GROUND_STATION_0', 'longitude_deg') # # CSV file name From 739a24151d47968f530d8916301f8b447d007e37 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 08:10:38 +0100 Subject: [PATCH 0142/1086] Fix PowerPort to POWER_PORT --- data/sample/initialize_files/components/gnss_receiver.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/gnss_receiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini index b9ff2d946..f71461156 100644 --- a/data/sample/initialize_files/components/gnss_receiver.ini +++ b/data/sample/initialize_files/components/gnss_receiver.ini @@ -38,6 +38,6 @@ white_noise_standard_deviation_eci_m(0) = 10000.0 white_noise_standard_deviation_eci_m(1) = 1000.0 white_noise_standard_deviation_eci_m(2) = 1000.0 -[PowerPort] +[POWER_PORT] minimum_voltage_V = 3.3 assumed_power_consumption_W = 1.0 From 7cdd9abe9095035c8d23614fc10900015a8c32a5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 14:13:10 +0100 Subject: [PATCH 0143/1086] Add id info for RW --- src/Component/AOCS/InitRwModel.cpp | 4 ++-- src/Component/AOCS/RWModel.cpp | 19 +++++++++++-------- src/Component/AOCS/RWModel.h | 7 +++++-- 3 files changed, 18 insertions(+), 12 deletions(-) diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index 2298f727d..b318a7f67 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -101,7 +101,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, + RWModel rwmodel(prescaler, fast_prescaler, clock_gen, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); @@ -115,7 +115,7 @@ RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuat power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, + RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); diff --git a/src/Component/AOCS/RWModel.cpp b/src/Component/AOCS/RWModel.cpp index 474f0d89b..30175c461 100644 --- a/src/Component/AOCS/RWModel.cpp +++ b/src/Component/AOCS/RWModel.cpp @@ -17,13 +17,14 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, double step_width, double dt_main_routine, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, const int id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, Vector<3> pos_b, double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : ComponentBase(prescaler, clock_gen, fast_prescaler), + id_(id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), @@ -43,13 +44,14 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, d Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, double step_width, double dt_main_routine, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, Vector<3> pos_b, double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : ComponentBase(prescaler, clock_gen, power_port, fast_prescaler), + id_(id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), @@ -180,15 +182,16 @@ void RWModel::SetVelocityLimitRpm(double velocity_limit_rpm) { std::string RWModel::GetLogHeader() const { std::string str_tmp = ""; + std::string component_name = "rw" + std::to_string(static_cast(id_)) + "_"; - str_tmp += WriteScalar("rw_angular_velocity", "rad/s"); - str_tmp += WriteScalar("rw_angular_velocity", "rpm"); - str_tmp += WriteScalar("rw_angular_velocity_upper_limit", "rpm"); - str_tmp += WriteScalar("rw_angular_acceleration", "rad/s2"); + str_tmp += WriteScalar(component_name + "angular_velocity", "rad/s"); + str_tmp += WriteScalar(component_name + "angular_velocity", "rpm"); + str_tmp += WriteScalar(component_name + "angular_velocity_upper_limit", "rpm"); + str_tmp += WriteScalar(component_name + "angular_acceleration", "rad/s2"); if (is_logged_jitter_) { - str_tmp += WriteVector("rw_jitter_force", "c", "N", 3); - str_tmp += WriteVector("rw_jitter_torque", "c", "Nm", 3); + str_tmp += WriteVector(component_name + "jitter_force", "c", "N", 3); + str_tmp += WriteVector(component_name + "jitter_torque", "c", "Nm", 3); } return str_tmp; diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index 8c9e0036a..844f3e416 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -31,6 +31,7 @@ class RWModel : public ComponentBase, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] fast_prescaler: Frequency scale factor for fast update * @param [in] clock_gen: Clock generator + * @param [in] id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] @@ -53,7 +54,7 @@ class RWModel : public ComponentBase, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const double step_width, const double dt_main_routine, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const Quaternion q_b2c, const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, const Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, @@ -66,6 +67,7 @@ class RWModel : public ComponentBase, public ILoggable { * @param [in] fast_prescaler: Frequency scale factor for fast update * @param [in] clock_gen: Clock generator * @param [in] power_port: Power port + * @param [in] id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] @@ -88,7 +90,7 @@ class RWModel : public ComponentBase, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const double step_width, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const Quaternion q_b2c, const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, const Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -181,6 +183,7 @@ class RWModel : public ComponentBase, public ILoggable { protected: // Fixed Parameters + const int id_; //!< Actuator ID const double inertia_; //!< Inertia of RW rotor [kgm2] const double max_torque_; //!< Maximum output torque [Nm] const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] From f164e9622f00a39fc3150f23341840a4d0e2e42f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 14:28:47 +0100 Subject: [PATCH 0144/1086] Fix format --- src/Component/AOCS/InitRwModel.cpp | 16 ++++++++-------- src/Component/AOCS/RWModel.cpp | 8 ++++---- src/Component/AOCS/RWModel.h | 13 +++++++------ 3 files changed, 19 insertions(+), 18 deletions(-) diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index b318a7f67..fdad97695 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -101,10 +101,10 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, - pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, - radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, - init_velocity); + RWModel rwmodel(prescaler, fast_prescaler, clock_gen, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, + max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, + radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, + considers_structural_resonance, drive_flag, init_velocity); return rwmodel; } @@ -115,10 +115,10 @@ RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuat power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, - max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, - radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, - considers_structural_resonance, drive_flag, init_velocity); + RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, + max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, + is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, + bandwidth, considers_structural_resonance, drive_flag, init_velocity); return rwmodel; } diff --git a/src/Component/AOCS/RWModel.cpp b/src/Component/AOCS/RWModel.cpp index 30175c461..82622e372 100644 --- a/src/Component/AOCS/RWModel.cpp +++ b/src/Component/AOCS/RWModel.cpp @@ -44,10 +44,10 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, c Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, double step_width, double dt_main_routine, - double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, Vector<3> pos_b, - double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, double step_width, + double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, + Vector<3> pos_b, double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, + bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : ComponentBase(prescaler, clock_gen, power_port, fast_prescaler), diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index 844f3e416..18f0ffc21 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -54,12 +54,13 @@ class RWModel : public ComponentBase, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const int id, const double step_width, const double dt_main_routine, - const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const Quaternion q_b2c, - const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, const Vector<3> coasting_lag_coef, - bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, - std::vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, - bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const int id, const double step_width, + const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, + const double max_velocity_rpm, const Quaternion q_b2c, const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, + const Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, + std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, + double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, + const bool drive_flag = false, const double init_velocity = 0.0); /** * @fn RWModel * @brief Constructor with power port From ef707ac08b0b67bf516ced38dff54a5bbba61eb9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 14:54:05 +0100 Subject: [PATCH 0145/1086] Fix PCU initial study --- data/sample/initialize_files/components/pcu_initial_study.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/pcu_initial_study.ini b/data/sample/initialize_files/components/pcu_initial_study.ini index 74140d813..0427c1efa 100644 --- a/data/sample/initialize_files/components/pcu_initial_study.ini +++ b/data/sample/initialize_files/components/pcu_initial_study.ini @@ -1,2 +1,2 @@ -[PCU_INITIAL_STUDY1] +[PCU_INITIAL_STUDY_1] prescaler = 10 From 78081d8801e95fd43f47bc76bf150a3500414230 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:08:13 +0100 Subject: [PATCH 0146/1086] Fix GNSS receiver to add ID --- .../initialize_files/components/gnss_receiver.ini | 2 +- src/Component/AOCS/InitGnssReceiver.cpp | 10 ++++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/data/sample/initialize_files/components/gnss_receiver.ini b/data/sample/initialize_files/components/gnss_receiver.ini index f71461156..a17ed683e 100644 --- a/data/sample/initialize_files/components/gnss_receiver.ini +++ b/data/sample/initialize_files/components/gnss_receiver.ini @@ -1,4 +1,4 @@ -[GNSS_RECEIVER] +[GNSS_RECEIVER_1] prescaler = 10 // Position of antenna at body frame [m] diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index ff916653b..89f46de88 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -19,11 +19,13 @@ typedef struct _gnssrecever_param { Vector<3> noise_std; } GNSSReceiverParam; -GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites) { +GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites, const int id) { GNSSReceiverParam gnssreceiver_param; IniAccess gnssr_conf(fname); - char GSection[30] = "GNSS_RECEIVER"; + const char* sensor_name = "GNSS_RECEIVER_"; + const std::string section_name = sensor_name + std::to_string(static_cast(id)); + const char* GSection = section_name.c_str(); int prescaler = gnssr_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -49,7 +51,7 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime) { - GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites); + GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); GNSSReceiver gnss_r(gr_param.prescaler, clock_gen, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); @@ -58,7 +60,7 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime) { - GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites); + GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); // PowerPort power_port->InitializeWithInitializeFile(fname); From 734608a5810d20baff1971ef33286efffd5bf1fe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:15:02 +0100 Subject: [PATCH 0147/1086] Fix GYRO to add ID --- data/sample/initialize_files/components/gyro_sensor.ini | 2 +- src/Component/AOCS/InitGyro.cpp | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index 41b423bf7..2a60224fa 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -1,4 +1,4 @@ -[GYRO_SENSOR] +[GYRO_SENSOR_1] prescaler = 10 // Quaternion from body frame to component frame diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 4fb96486f..0590c6c4a 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -10,7 +10,9 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); - char GSection[30] = "GYRO_SENSOR"; + const char* sensor_name = "GYRO_SENSOR_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* GSection = section_name.c_str(); Quaternion q_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); @@ -28,7 +30,9 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); - char GSection[30] = "GYRO_SENSOR"; + const char* sensor_name = "GYRO_SENSOR_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* GSection = section_name.c_str(); Quaternion q_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); From 2db339892746d1980c6e095f0e3f29ed9bfcb6e8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:16:18 +0100 Subject: [PATCH 0148/1086] Fix small --- data/sample/initialize_files/components/gyro_sensor.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index 2a60224fa..32b0c51cb 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -8,7 +8,7 @@ quaternion_b2c(1) = 0.0 quaternion_b2c(2) = 0.0 quaternion_b2c(3) = 1.0 -[SENSOR_BASE_GYRO_SENSOR] +[SENSOR_BASE_GYRO_SENSOR_1] // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), scale_factor_c(0) = 1.0 From 2d4d744211e4726cf94226429fd8b9480c74d6c2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:18:35 +0100 Subject: [PATCH 0149/1086] Fix MAGNETOMETER to add ID --- data/sample/initialize_files/components/magnetometer.ini | 4 ++-- src/Component/AOCS/InitMagSensor.cpp | 8 ++++++-- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/data/sample/initialize_files/components/magnetometer.ini b/data/sample/initialize_files/components/magnetometer.ini index 6561e41f6..7023ebca2 100644 --- a/data/sample/initialize_files/components/magnetometer.ini +++ b/data/sample/initialize_files/components/magnetometer.ini @@ -1,4 +1,4 @@ -[MAGNETOMETER] +[MAGNETOMETER_1] prescaler = 10 //Quaternion from body frame to component frame @@ -7,7 +7,7 @@ quaternion_b2c(1) = 0.0 quaternion_b2c(2) = 0.0 quaternion_b2c(3) = 1.0 -[SENSOR_BASE_MAGNETOMETER] +[SENSOR_BASE_MAGNETOMETER_1] // Sensor Base // Scale Factor Matrix (3×3) // (0) = (0,0), (1) = (0,1), (2) = (0,2), diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index 05adb2465..ae3e780ef 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -9,7 +9,9 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); - char MSSection[30] = "MAGNETOMETER"; + const char* sensor_name = "MAGNETOMETER_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* MSSection = section_name.c_str(); int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -27,7 +29,9 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); - char MSSection[30] = "MAGNETOMETER"; + const char* sensor_name = "MAGNETOMETER_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* MSSection = section_name.c_str(); int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; From 2e4bdf27fb30c3a02a695d51bce5315805845104 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:21:05 +0100 Subject: [PATCH 0150/1086] Fix MAGNETORQUER to add ID --- data/sample/initialize_files/components/magnetorquer.ini | 2 +- src/Component/AOCS/InitMagTorquer.cpp | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/components/magnetorquer.ini b/data/sample/initialize_files/components/magnetorquer.ini index 42eabadbc..c74f4bb03 100644 --- a/data/sample/initialize_files/components/magnetorquer.ini +++ b/data/sample/initialize_files/components/magnetorquer.ini @@ -1,4 +1,4 @@ -[MAGNETORQUER] +[MAGNETORQUER_1] prescaler = 10 //Quaternion from body frame to component frame diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index b404403bc..05cf48a7d 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -9,7 +9,9 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { IniAccess magtorquer_conf(fname); - char MTSection[30] = "MAGNETORQUER"; + const char* sensor_name = "MAGNETORQUER_"; + const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); + const char* MTSection = section_name.c_str(); int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -51,7 +53,9 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { IniAccess magtorquer_conf(fname); - char MTSection[30] = "MAGNETORQUER"; + const char* sensor_name = "MAGNETORQUER_"; + const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); + const char* MTSection = section_name.c_str(); int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; From 2d447c02c0e5dc456082eaacf1fe515caf007f1a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 15:24:02 +0100 Subject: [PATCH 0151/1086] Fix STT to add ID --- .../sample/initialize_files/components/star_sensor.ini | 2 +- src/Component/AOCS/InitStt.cpp | 10 ++++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/data/sample/initialize_files/components/star_sensor.ini b/data/sample/initialize_files/components/star_sensor.ini index 3b9c70159..7b62234de 100644 --- a/data/sample/initialize_files/components/star_sensor.ini +++ b/data/sample/initialize_files/components/star_sensor.ini @@ -1,4 +1,4 @@ -[STAR_SENSOR] +[STAR_SENSOR_1] prescaler = 10; // Quaternion from body frame to component frame diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index d4c3b9323..e123ab1fa 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -13,8 +13,9 @@ using namespace std; STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); - string section_tmp = "STAR_SENSOR"; - const char* STTSection = section_tmp.data(); + const char* sensor_name = "STAR_SENSOR_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* STTSection = section_name.c_str(); int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -44,8 +45,9 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); - string section_tmp = "STAR_SENSOR"; - const char* STTSection = section_tmp.data(); + const char* sensor_name = "STAR_SENSOR_"; + const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); + const char* STTSection = section_name.c_str(); int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; From 3fb741d38c22cb836739002157f8ba8893b07aab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 6 Feb 2023 21:40:08 +0100 Subject: [PATCH 0152/1086] Rename s2e.cpp --- src/{S2E.cpp => s2e.cpp} | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) rename src/{S2E.cpp => s2e.cpp} (99%) diff --git a/src/S2E.cpp b/src/s2e.cpp similarity index 99% rename from src/S2E.cpp rename to src/s2e.cpp index fc52a4b52..869d8265a 100644 --- a/src/S2E.cpp +++ b/src/s2e.cpp @@ -1,5 +1,5 @@ /** - * @file S2E.cpp + * @file s2e.cpp * @brief The main file of S2E */ From a3b30863bfbcd77fbce390f2198dac8f158918e4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:09:34 +0100 Subject: [PATCH 0153/1086] Rename Simulation directory --- src/{Simulation => simulation}/CMakeLists.txt | 0 src/{Simulation => simulation}/Case/SampleCase.cpp | 0 src/{Simulation => simulation}/Case/SampleCase.h | 0 src/{Simulation => simulation}/Case/SimulationCase.cpp | 0 src/{Simulation => simulation}/Case/SimulationCase.h | 0 src/{Simulation => simulation}/GroundStation/GroundStation.cpp | 0 src/{Simulation => simulation}/GroundStation/GroundStation.h | 0 .../GroundStation/SampleGroundStation/SampleGS.cpp | 0 .../GroundStation/SampleGroundStation/SampleGS.h | 0 .../GroundStation/SampleGroundStation/SampleGSComponents.cpp | 0 .../GroundStation/SampleGroundStation/SampleGSComponents.h | 0 src/{Simulation => simulation}/InterSatComm/InterSatComm.cpp | 0 src/{Simulation => simulation}/InterSatComm/InterSatComm.h | 0 src/{Simulation => simulation}/MCSim/InitMcSim.cpp | 0 src/{Simulation => simulation}/MCSim/InitMcSim.hpp | 0 src/{Simulation => simulation}/MCSim/InitParameter.cpp | 0 src/{Simulation => simulation}/MCSim/InitParameter.h | 0 src/{Simulation => simulation}/MCSim/MCSimExecutor.cpp | 0 src/{Simulation => simulation}/MCSim/MCSimExecutor.h | 0 src/{Simulation => simulation}/MCSim/SimulationObject.cpp | 0 src/{Simulation => simulation}/MCSim/SimulationObject.h | 0 src/{Simulation => simulation}/SimulationConfig.h | 0 src/{Simulation => simulation}/Spacecraft/InstalledComponents.cpp | 0 src/{Simulation => simulation}/Spacecraft/InstalledComponents.hpp | 0 .../Spacecraft/SampleSpacecraft/SampleComponents.cpp | 0 .../Spacecraft/SampleSpacecraft/SampleComponents.h | 0 .../Spacecraft/SampleSpacecraft/SampleSat.cpp | 0 .../Spacecraft/SampleSpacecraft/SampleSat.h | 0 .../Spacecraft/SampleSpacecraft/Sample_PortConfig.h | 0 src/{Simulation => simulation}/Spacecraft/Spacecraft.cpp | 0 src/{Simulation => simulation}/Spacecraft/Spacecraft.h | 0 .../Spacecraft/Structure/InitStructure.cpp | 0 .../Spacecraft/Structure/InitStructure.hpp | 0 .../Spacecraft/Structure/KinematicsParams.cpp | 0 .../Spacecraft/Structure/KinematicsParams.h | 0 src/{Simulation => simulation}/Spacecraft/Structure/RMMParams.cpp | 0 src/{Simulation => simulation}/Spacecraft/Structure/RMMParams.h | 0 src/{Simulation => simulation}/Spacecraft/Structure/Structure.cpp | 0 src/{Simulation => simulation}/Spacecraft/Structure/Structure.h | 0 src/{Simulation => simulation}/Spacecraft/Structure/Surface.cpp | 0 src/{Simulation => simulation}/Spacecraft/Structure/Surface.h | 0 41 files changed, 0 insertions(+), 0 deletions(-) rename src/{Simulation => simulation}/CMakeLists.txt (100%) rename src/{Simulation => simulation}/Case/SampleCase.cpp (100%) rename src/{Simulation => simulation}/Case/SampleCase.h (100%) rename src/{Simulation => simulation}/Case/SimulationCase.cpp (100%) rename src/{Simulation => simulation}/Case/SimulationCase.h (100%) rename src/{Simulation => simulation}/GroundStation/GroundStation.cpp (100%) rename src/{Simulation => simulation}/GroundStation/GroundStation.h (100%) rename src/{Simulation => simulation}/GroundStation/SampleGroundStation/SampleGS.cpp (100%) rename src/{Simulation => simulation}/GroundStation/SampleGroundStation/SampleGS.h (100%) rename src/{Simulation => simulation}/GroundStation/SampleGroundStation/SampleGSComponents.cpp (100%) rename src/{Simulation => simulation}/GroundStation/SampleGroundStation/SampleGSComponents.h (100%) rename src/{Simulation => simulation}/InterSatComm/InterSatComm.cpp (100%) rename src/{Simulation => simulation}/InterSatComm/InterSatComm.h (100%) rename src/{Simulation => simulation}/MCSim/InitMcSim.cpp (100%) rename src/{Simulation => simulation}/MCSim/InitMcSim.hpp (100%) rename src/{Simulation => simulation}/MCSim/InitParameter.cpp (100%) rename src/{Simulation => simulation}/MCSim/InitParameter.h (100%) rename src/{Simulation => simulation}/MCSim/MCSimExecutor.cpp (100%) rename src/{Simulation => simulation}/MCSim/MCSimExecutor.h (100%) rename src/{Simulation => simulation}/MCSim/SimulationObject.cpp (100%) rename src/{Simulation => simulation}/MCSim/SimulationObject.h (100%) rename src/{Simulation => simulation}/SimulationConfig.h (100%) rename src/{Simulation => simulation}/Spacecraft/InstalledComponents.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/InstalledComponents.hpp (100%) rename src/{Simulation => simulation}/Spacecraft/SampleSpacecraft/SampleComponents.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/SampleSpacecraft/SampleComponents.h (100%) rename src/{Simulation => simulation}/Spacecraft/SampleSpacecraft/SampleSat.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/SampleSpacecraft/SampleSat.h (100%) rename src/{Simulation => simulation}/Spacecraft/SampleSpacecraft/Sample_PortConfig.h (100%) rename src/{Simulation => simulation}/Spacecraft/Spacecraft.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Spacecraft.h (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/InitStructure.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/InitStructure.hpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/KinematicsParams.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/KinematicsParams.h (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/RMMParams.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/RMMParams.h (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/Structure.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/Structure.h (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/Surface.cpp (100%) rename src/{Simulation => simulation}/Spacecraft/Structure/Surface.h (100%) diff --git a/src/Simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt similarity index 100% rename from src/Simulation/CMakeLists.txt rename to src/simulation/CMakeLists.txt diff --git a/src/Simulation/Case/SampleCase.cpp b/src/simulation/Case/SampleCase.cpp similarity index 100% rename from src/Simulation/Case/SampleCase.cpp rename to src/simulation/Case/SampleCase.cpp diff --git a/src/Simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h similarity index 100% rename from src/Simulation/Case/SampleCase.h rename to src/simulation/Case/SampleCase.h diff --git a/src/Simulation/Case/SimulationCase.cpp b/src/simulation/Case/SimulationCase.cpp similarity index 100% rename from src/Simulation/Case/SimulationCase.cpp rename to src/simulation/Case/SimulationCase.cpp diff --git a/src/Simulation/Case/SimulationCase.h b/src/simulation/Case/SimulationCase.h similarity index 100% rename from src/Simulation/Case/SimulationCase.h rename to src/simulation/Case/SimulationCase.h diff --git a/src/Simulation/GroundStation/GroundStation.cpp b/src/simulation/GroundStation/GroundStation.cpp similarity index 100% rename from src/Simulation/GroundStation/GroundStation.cpp rename to src/simulation/GroundStation/GroundStation.cpp diff --git a/src/Simulation/GroundStation/GroundStation.h b/src/simulation/GroundStation/GroundStation.h similarity index 100% rename from src/Simulation/GroundStation/GroundStation.h rename to src/simulation/GroundStation/GroundStation.h diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGS.cpp b/src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp similarity index 100% rename from src/Simulation/GroundStation/SampleGroundStation/SampleGS.cpp rename to src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGS.h b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h similarity index 100% rename from src/Simulation/GroundStation/SampleGroundStation/SampleGS.h rename to src/simulation/GroundStation/SampleGroundStation/SampleGS.h diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp b/src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp similarity index 100% rename from src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp rename to src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp diff --git a/src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.h b/src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.h similarity index 100% rename from src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.h rename to src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.h diff --git a/src/Simulation/InterSatComm/InterSatComm.cpp b/src/simulation/InterSatComm/InterSatComm.cpp similarity index 100% rename from src/Simulation/InterSatComm/InterSatComm.cpp rename to src/simulation/InterSatComm/InterSatComm.cpp diff --git a/src/Simulation/InterSatComm/InterSatComm.h b/src/simulation/InterSatComm/InterSatComm.h similarity index 100% rename from src/Simulation/InterSatComm/InterSatComm.h rename to src/simulation/InterSatComm/InterSatComm.h diff --git a/src/Simulation/MCSim/InitMcSim.cpp b/src/simulation/MCSim/InitMcSim.cpp similarity index 100% rename from src/Simulation/MCSim/InitMcSim.cpp rename to src/simulation/MCSim/InitMcSim.cpp diff --git a/src/Simulation/MCSim/InitMcSim.hpp b/src/simulation/MCSim/InitMcSim.hpp similarity index 100% rename from src/Simulation/MCSim/InitMcSim.hpp rename to src/simulation/MCSim/InitMcSim.hpp diff --git a/src/Simulation/MCSim/InitParameter.cpp b/src/simulation/MCSim/InitParameter.cpp similarity index 100% rename from src/Simulation/MCSim/InitParameter.cpp rename to src/simulation/MCSim/InitParameter.cpp diff --git a/src/Simulation/MCSim/InitParameter.h b/src/simulation/MCSim/InitParameter.h similarity index 100% rename from src/Simulation/MCSim/InitParameter.h rename to src/simulation/MCSim/InitParameter.h diff --git a/src/Simulation/MCSim/MCSimExecutor.cpp b/src/simulation/MCSim/MCSimExecutor.cpp similarity index 100% rename from src/Simulation/MCSim/MCSimExecutor.cpp rename to src/simulation/MCSim/MCSimExecutor.cpp diff --git a/src/Simulation/MCSim/MCSimExecutor.h b/src/simulation/MCSim/MCSimExecutor.h similarity index 100% rename from src/Simulation/MCSim/MCSimExecutor.h rename to src/simulation/MCSim/MCSimExecutor.h diff --git a/src/Simulation/MCSim/SimulationObject.cpp b/src/simulation/MCSim/SimulationObject.cpp similarity index 100% rename from src/Simulation/MCSim/SimulationObject.cpp rename to src/simulation/MCSim/SimulationObject.cpp diff --git a/src/Simulation/MCSim/SimulationObject.h b/src/simulation/MCSim/SimulationObject.h similarity index 100% rename from src/Simulation/MCSim/SimulationObject.h rename to src/simulation/MCSim/SimulationObject.h diff --git a/src/Simulation/SimulationConfig.h b/src/simulation/SimulationConfig.h similarity index 100% rename from src/Simulation/SimulationConfig.h rename to src/simulation/SimulationConfig.h diff --git a/src/Simulation/Spacecraft/InstalledComponents.cpp b/src/simulation/Spacecraft/InstalledComponents.cpp similarity index 100% rename from src/Simulation/Spacecraft/InstalledComponents.cpp rename to src/simulation/Spacecraft/InstalledComponents.cpp diff --git a/src/Simulation/Spacecraft/InstalledComponents.hpp b/src/simulation/Spacecraft/InstalledComponents.hpp similarity index 100% rename from src/Simulation/Spacecraft/InstalledComponents.hpp rename to src/simulation/Spacecraft/InstalledComponents.hpp diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp similarity index 100% rename from src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp rename to src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h similarity index 100% rename from src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.h rename to src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp b/src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp similarity index 100% rename from src/Simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp rename to src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/SampleSat.h b/src/simulation/Spacecraft/SampleSpacecraft/SampleSat.h similarity index 100% rename from src/Simulation/Spacecraft/SampleSpacecraft/SampleSat.h rename to src/simulation/Spacecraft/SampleSpacecraft/SampleSat.h diff --git a/src/Simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h b/src/simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h similarity index 100% rename from src/Simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h rename to src/simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h diff --git a/src/Simulation/Spacecraft/Spacecraft.cpp b/src/simulation/Spacecraft/Spacecraft.cpp similarity index 100% rename from src/Simulation/Spacecraft/Spacecraft.cpp rename to src/simulation/Spacecraft/Spacecraft.cpp diff --git a/src/Simulation/Spacecraft/Spacecraft.h b/src/simulation/Spacecraft/Spacecraft.h similarity index 100% rename from src/Simulation/Spacecraft/Spacecraft.h rename to src/simulation/Spacecraft/Spacecraft.h diff --git a/src/Simulation/Spacecraft/Structure/InitStructure.cpp b/src/simulation/Spacecraft/Structure/InitStructure.cpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/InitStructure.cpp rename to src/simulation/Spacecraft/Structure/InitStructure.cpp diff --git a/src/Simulation/Spacecraft/Structure/InitStructure.hpp b/src/simulation/Spacecraft/Structure/InitStructure.hpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/InitStructure.hpp rename to src/simulation/Spacecraft/Structure/InitStructure.hpp diff --git a/src/Simulation/Spacecraft/Structure/KinematicsParams.cpp b/src/simulation/Spacecraft/Structure/KinematicsParams.cpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/KinematicsParams.cpp rename to src/simulation/Spacecraft/Structure/KinematicsParams.cpp diff --git a/src/Simulation/Spacecraft/Structure/KinematicsParams.h b/src/simulation/Spacecraft/Structure/KinematicsParams.h similarity index 100% rename from src/Simulation/Spacecraft/Structure/KinematicsParams.h rename to src/simulation/Spacecraft/Structure/KinematicsParams.h diff --git a/src/Simulation/Spacecraft/Structure/RMMParams.cpp b/src/simulation/Spacecraft/Structure/RMMParams.cpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/RMMParams.cpp rename to src/simulation/Spacecraft/Structure/RMMParams.cpp diff --git a/src/Simulation/Spacecraft/Structure/RMMParams.h b/src/simulation/Spacecraft/Structure/RMMParams.h similarity index 100% rename from src/Simulation/Spacecraft/Structure/RMMParams.h rename to src/simulation/Spacecraft/Structure/RMMParams.h diff --git a/src/Simulation/Spacecraft/Structure/Structure.cpp b/src/simulation/Spacecraft/Structure/Structure.cpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/Structure.cpp rename to src/simulation/Spacecraft/Structure/Structure.cpp diff --git a/src/Simulation/Spacecraft/Structure/Structure.h b/src/simulation/Spacecraft/Structure/Structure.h similarity index 100% rename from src/Simulation/Spacecraft/Structure/Structure.h rename to src/simulation/Spacecraft/Structure/Structure.h diff --git a/src/Simulation/Spacecraft/Structure/Surface.cpp b/src/simulation/Spacecraft/Structure/Surface.cpp similarity index 100% rename from src/Simulation/Spacecraft/Structure/Surface.cpp rename to src/simulation/Spacecraft/Structure/Surface.cpp diff --git a/src/Simulation/Spacecraft/Structure/Surface.h b/src/simulation/Spacecraft/Structure/Surface.h similarity index 100% rename from src/Simulation/Spacecraft/Structure/Surface.h rename to src/simulation/Spacecraft/Structure/Surface.h From 5510d2f65691ab4ab356bf826ec3a0e60f3fff76 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:22:41 +0100 Subject: [PATCH 0154/1086] Rename SimulationConfig --- .../{SimulationConfig.h => simulation_configuration.hpp} | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) rename src/simulation/{SimulationConfig.h => simulation_configuration.hpp} (82%) diff --git a/src/simulation/SimulationConfig.h b/src/simulation/simulation_configuration.hpp similarity index 82% rename from src/simulation/SimulationConfig.h rename to src/simulation/simulation_configuration.hpp index da96bc405..38151233c 100644 --- a/src/simulation/SimulationConfig.h +++ b/src/simulation/simulation_configuration.hpp @@ -1,9 +1,11 @@ /** - * @file SimulationConfig.h + * @file simulation_configuration.hpp * @brief Definition of struct for simulation setting information */ -#pragma once +#ifndef S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ +#define S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ + #include #include @@ -28,3 +30,5 @@ struct SimulationConfig { */ ~SimulationConfig() { delete main_logger_; } }; + +#endif // S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ From d8fcff8db01fda1c6439c4d259ef6b76c3ff9db5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:23:01 +0100 Subject: [PATCH 0155/1086] Fix include path for simulation directory --- CMakeLists.txt | 14 +++++++------- src/Component/CommGS/GScalculator.h | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- .../examples/example_change_structure.hpp | 2 +- src/Disturbance/Disturbances.h | 2 +- src/Disturbance/MagDisturbance.h | 2 +- src/Disturbance/SurfaceForce.h | 2 +- src/Dynamics/Attitude/Attitude.h | 2 +- src/Dynamics/Dynamics.h | 4 ++-- src/Environment/Global/GlobalEnvironment.h | 3 ++- src/Environment/Local/LocalEnvironment.h | 2 +- src/s2e.cpp | 4 ++-- src/simulation/Case/SimulationCase.h | 4 ++-- src/simulation/GroundStation/GroundStation.h | 4 ++-- src/simulation/InterSatComm/InterSatComm.h | 2 +- .../Spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- .../Spacecraft/Structure/InitStructure.hpp | 2 +- src/simulation/Spacecraft/Structure/Structure.cpp | 2 +- src/simulation/Spacecraft/Structure/Structure.h | 3 +-- 19 files changed, 30 insertions(+), 30 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 89bcf881e..a7570935d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -63,7 +63,7 @@ include_directories(${CSPICE_DIR}/include) include_directories(${NRLMSISE00_DIR}/src) ## add_subdirectories -add_subdirectory(src/Simulation) +add_subdirectory(src/simulation) add_subdirectory(src/Environment/Global) add_subdirectory(src/Environment/Local) add_subdirectory(src/Dynamics) @@ -86,12 +86,12 @@ add_subdirectory(src/Library/Orbit) add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES - src/S2E.cpp - src/Simulation/Case/SampleCase.cpp - src/Simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp - src/Simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp - src/Simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp - src/Simulation/GroundStation/SampleGroundStation/SampleGS.cpp + src/s2e.cpp + src/simulation/Case/SampleCase.cpp + src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp + src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp + src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp + src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp ) ## Create executable file diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index a0185fbe3..bb144920b 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 8ed2d8fb5..3cac402d5 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 8993b0ddd..0c2b79e93 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Disturbance/Disturbances.h b/src/Disturbance/Disturbances.h index 39ade5315..71f8f2926 100644 --- a/src/Disturbance/Disturbances.h +++ b/src/Disturbance/Disturbances.h @@ -8,7 +8,7 @@ #include #include "../Environment/Global/SimTime.h" -#include "../Simulation/Spacecraft/Structure/Structure.h" +#include "../simulation/Spacecraft/Structure/Structure.h" #include "AccelerationDisturbance.h" #include "SimpleDisturbance.h" diff --git a/src/Disturbance/MagDisturbance.h b/src/Disturbance/MagDisturbance.h index 8f5b34986..a52adff1a 100644 --- a/src/Disturbance/MagDisturbance.h +++ b/src/Disturbance/MagDisturbance.h @@ -12,7 +12,7 @@ using libra::Vector; #include "../Interface/LogOutput/ILoggable.h" -#include "../Simulation/Spacecraft/Structure/RMMParams.h" +#include "../simulation/Spacecraft/Structure/RMMParams.h" #include "SimpleDisturbance.h" /** diff --git a/src/Disturbance/SurfaceForce.h b/src/Disturbance/SurfaceForce.h index c56f06082..1f51fba77 100644 --- a/src/Disturbance/SurfaceForce.h +++ b/src/Disturbance/SurfaceForce.h @@ -10,7 +10,7 @@ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" -#include "../Simulation/Spacecraft/Structure/Surface.h" +#include "../simulation/Spacecraft/Structure/Surface.h" #include "SimpleDisturbance.h" using libra::Quaternion; using libra::Vector; diff --git a/src/Dynamics/Attitude/Attitude.h b/src/Dynamics/Attitude/Attitude.h index 4c45f7fa8..48f5253f6 100644 --- a/src/Dynamics/Attitude/Attitude.h +++ b/src/Dynamics/Attitude/Attitude.h @@ -6,7 +6,7 @@ #define __attitude_H__ #include -#include +#include #include #include diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index 621c6d652..5ed7f6201 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -17,8 +17,8 @@ using libra::Vector; #include "../Environment/Global/SimTime.h" #include "../Environment/Local/LocalCelestialInformation.h" -#include "../Simulation/SimulationConfig.h" -#include "../Simulation/Spacecraft/Structure/Structure.h" +#include "../simulation/Spacecraft/Structure/Structure.h" +#include "../simulation/simulation_configuration.hpp" #include "./Orbit/Orbit.h" #include "./Thermal/Temperature.h" diff --git a/src/Environment/Global/GlobalEnvironment.h b/src/Environment/Global/GlobalEnvironment.h index e5f5a112b..5da37477b 100644 --- a/src/Environment/Global/GlobalEnvironment.h +++ b/src/Environment/Global/GlobalEnvironment.h @@ -6,7 +6,8 @@ #pragma once #include -#include + +#include #include "CelestialInformation.h" #include "GnssSatellites.h" diff --git a/src/Environment/Local/LocalEnvironment.h b/src/Environment/Local/LocalEnvironment.h index 66ae514b5..9c427e209 100644 --- a/src/Environment/Local/LocalEnvironment.h +++ b/src/Environment/Local/LocalEnvironment.h @@ -11,7 +11,7 @@ #include "LocalCelestialInformation.h" #include "MagEnvironment.h" #include "SRPEnvironment.h" -#include "Simulation/SimulationConfig.h" +#include "simulation/simulation_configuration.hpp" class Logger; class SimTime; diff --git a/src/s2e.cpp b/src/s2e.cpp index 869d8265a..db41ee540 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -18,8 +18,8 @@ #include "Interface/LogOutput/Logger.h" // Add custom include files -#include "Simulation/Case/SampleCase.h" -// #include "Simulation/MCSim/MCSimExecutor.h" +#include "simulation/Case/SampleCase.h" +// #include "simulation/MCSim/MCSimExecutor.h" // #include "Interface/HilsInOut/COSMOSWrapper.h" // #include "Interface/HilsInOut/HardwareMessage.h" diff --git a/src/simulation/Case/SimulationCase.h b/src/simulation/Case/SimulationCase.h index 282a4e1f7..c3bd3083f 100644 --- a/src/simulation/Case/SimulationCase.h +++ b/src/simulation/Case/SimulationCase.h @@ -7,9 +7,9 @@ #include #include -#include +#include -#include "../SimulationConfig.h" +#include "../simulation_configuration.hpp" class Logger; /** diff --git a/src/simulation/GroundStation/GroundStation.h b/src/simulation/GroundStation/GroundStation.h index 4673579fa..e3060fdcb 100644 --- a/src/simulation/GroundStation/GroundStation.h +++ b/src/simulation/GroundStation/GroundStation.h @@ -6,12 +6,12 @@ #pragma once #include -#include +#include #include #include -#include "../SimulationConfig.h" +#include "../simulation_configuration.hpp" /** * @class GroundStation diff --git a/src/simulation/InterSatComm/InterSatComm.h b/src/simulation/InterSatComm/InterSatComm.h index 68d12e083..04aa4f737 100644 --- a/src/simulation/InterSatComm/InterSatComm.h +++ b/src/simulation/InterSatComm/InterSatComm.h @@ -5,7 +5,7 @@ #pragma once -#include "../SimulationConfig.h" +#include "../simulation_configuration.hpp" /** * @class InterSatComm diff --git a/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h index 940418721..885107af7 100644 --- a/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/simulation/Spacecraft/Structure/InitStructure.hpp b/src/simulation/Spacecraft/Structure/InitStructure.hpp index 61621e630..33eb09615 100644 --- a/src/simulation/Spacecraft/Structure/InitStructure.hpp +++ b/src/simulation/Spacecraft/Structure/InitStructure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitKinematicsParams diff --git a/src/simulation/Spacecraft/Structure/Structure.cpp b/src/simulation/Spacecraft/Structure/Structure.cpp index 003352481..3f4fd11fb 100644 --- a/src/simulation/Spacecraft/Structure/Structure.cpp +++ b/src/simulation/Spacecraft/Structure/Structure.cpp @@ -7,7 +7,7 @@ #include -#include +#include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } diff --git a/src/simulation/Spacecraft/Structure/Structure.h b/src/simulation/Spacecraft/Structure/Structure.h index a300ed765..d9c3a6311 100644 --- a/src/simulation/Spacecraft/Structure/Structure.h +++ b/src/simulation/Spacecraft/Structure/Structure.h @@ -4,8 +4,7 @@ */ #pragma once -#include - +#include #include #include "KinematicsParams.h" From f8c746ed1a60775810a3b3b496dc63d0ca3e4ba8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:27:34 +0100 Subject: [PATCH 0156/1086] Rename Spacecraft directory --- CMakeLists.txt | 4 ++-- src/Component/Propulsion/SimpleThruster.h | 2 +- .../examples/example_change_structure.hpp | 2 +- src/Disturbance/Disturbances.h | 2 +- src/Disturbance/MagDisturbance.h | 2 +- src/Disturbance/SurfaceForce.h | 2 +- src/Dynamics/Dynamics.h | 2 +- src/simulation/CMakeLists.txt | 14 +++++++------- src/simulation/Case/SampleCase.cpp | 2 +- src/simulation/Case/SampleCase.h | 2 +- src/simulation/GroundStation/GroundStation.h | 2 +- .../GroundStation/SampleGroundStation/SampleGS.h | 2 +- .../InstalledComponents.cpp | 0 .../InstalledComponents.hpp | 0 .../SampleSpacecraft/SampleComponents.cpp | 0 .../SampleSpacecraft/SampleComponents.h | 2 +- .../SampleSpacecraft/SampleSat.cpp | 0 .../SampleSpacecraft/SampleSat.h | 0 .../SampleSpacecraft/Sample_PortConfig.h | 0 .../{Spacecraft => spacecraft}/Spacecraft.cpp | 0 .../{Spacecraft => spacecraft}/Spacecraft.h | 0 .../Structure/InitStructure.cpp | 0 .../Structure/InitStructure.hpp | 2 +- .../Structure/KinematicsParams.cpp | 0 .../Structure/KinematicsParams.h | 0 .../Structure/RMMParams.cpp | 0 .../Structure/RMMParams.h | 0 .../Structure/Structure.cpp | 2 +- .../Structure/Structure.h | 0 .../Structure/Surface.cpp | 0 .../{Spacecraft => spacecraft}/Structure/Surface.h | 0 31 files changed, 22 insertions(+), 22 deletions(-) rename src/simulation/{Spacecraft => spacecraft}/InstalledComponents.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/InstalledComponents.hpp (100%) rename src/simulation/{Spacecraft => spacecraft}/SampleSpacecraft/SampleComponents.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/SampleSpacecraft/SampleComponents.h (98%) rename src/simulation/{Spacecraft => spacecraft}/SampleSpacecraft/SampleSat.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/SampleSpacecraft/SampleSat.h (100%) rename src/simulation/{Spacecraft => spacecraft}/SampleSpacecraft/Sample_PortConfig.h (100%) rename src/simulation/{Spacecraft => spacecraft}/Spacecraft.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/Spacecraft.h (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/InitStructure.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/InitStructure.hpp (91%) rename src/simulation/{Spacecraft => spacecraft}/Structure/KinematicsParams.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/KinematicsParams.h (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/RMMParams.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/RMMParams.h (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/Structure.cpp (93%) rename src/simulation/{Spacecraft => spacecraft}/Structure/Structure.h (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/Surface.cpp (100%) rename src/simulation/{Spacecraft => spacecraft}/Structure/Surface.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index a7570935d..5dd5d6018 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,8 +88,8 @@ add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES src/s2e.cpp src/simulation/Case/SampleCase.cpp - src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp - src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp + src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp + src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp ) diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 3cac402d5..075dbba9e 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 0c2b79e93..cecb8b00c 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Disturbance/Disturbances.h b/src/Disturbance/Disturbances.h index 71f8f2926..1f54c0455 100644 --- a/src/Disturbance/Disturbances.h +++ b/src/Disturbance/Disturbances.h @@ -8,7 +8,7 @@ #include #include "../Environment/Global/SimTime.h" -#include "../simulation/Spacecraft/Structure/Structure.h" +#include "../simulation/spacecraft/Structure/Structure.h" #include "AccelerationDisturbance.h" #include "SimpleDisturbance.h" diff --git a/src/Disturbance/MagDisturbance.h b/src/Disturbance/MagDisturbance.h index a52adff1a..d1f83fa97 100644 --- a/src/Disturbance/MagDisturbance.h +++ b/src/Disturbance/MagDisturbance.h @@ -12,7 +12,7 @@ using libra::Vector; #include "../Interface/LogOutput/ILoggable.h" -#include "../simulation/Spacecraft/Structure/RMMParams.h" +#include "../simulation/spacecraft/Structure/RMMParams.h" #include "SimpleDisturbance.h" /** diff --git a/src/Disturbance/SurfaceForce.h b/src/Disturbance/SurfaceForce.h index 1f51fba77..66db1d503 100644 --- a/src/Disturbance/SurfaceForce.h +++ b/src/Disturbance/SurfaceForce.h @@ -10,7 +10,7 @@ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" -#include "../simulation/Spacecraft/Structure/Surface.h" +#include "../simulation/spacecraft/Structure/Surface.h" #include "SimpleDisturbance.h" using libra::Quaternion; using libra::Vector; diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index 5ed7f6201..68714834b 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -17,8 +17,8 @@ using libra::Vector; #include "../Environment/Global/SimTime.h" #include "../Environment/Local/LocalCelestialInformation.h" -#include "../simulation/Spacecraft/Structure/Structure.h" #include "../simulation/simulation_configuration.hpp" +#include "../simulation/spacecraft/Structure/Structure.h" #include "./Orbit/Orbit.h" #include "./Thermal/Temperature.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 00af8c19b..cae6bef58 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -9,13 +9,13 @@ add_library(${PROJECT_NAME} STATIC MCSim/SimulationObject.cpp MCSim/InitMcSim.cpp - Spacecraft/Spacecraft.cpp - Spacecraft/InstalledComponents.cpp - Spacecraft/Structure/Structure.cpp - Spacecraft/Structure/KinematicsParams.cpp - Spacecraft/Structure/RMMParams.cpp - Spacecraft/Structure/Surface.cpp - Spacecraft/Structure/InitStructure.cpp + spacecraft/Spacecraft.cpp + spacecraft/InstalledComponents.cpp + spacecraft/Structure/Structure.cpp + spacecraft/Structure/KinematicsParams.cpp + spacecraft/Structure/RMMParams.cpp + spacecraft/Structure/Surface.cpp + spacecraft/Structure/InitStructure.cpp GroundStation/GroundStation.cpp diff --git a/src/simulation/Case/SampleCase.cpp b/src/simulation/Case/SampleCase.cpp index 990e981eb..4ee431942 100644 --- a/src/simulation/Case/SampleCase.cpp +++ b/src/simulation/Case/SampleCase.cpp @@ -5,7 +5,7 @@ #include "SampleCase.h" -#include "../Spacecraft/SampleSpacecraft/SampleSat.h" +#include "../spacecraft/SampleSpacecraft/SampleSat.h" using std::cout; using std::string; diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h index ad42851a1..16c3146bf 100644 --- a/src/simulation/Case/SampleCase.h +++ b/src/simulation/Case/SampleCase.h @@ -6,7 +6,7 @@ #pragma once #include "../GroundStation/SampleGroundStation/SampleGS.h" -#include "../Spacecraft/SampleSpacecraft/SampleSat.h" +#include "../spacecraft/SampleSpacecraft/SampleSat.h" #include "./SimulationCase.h" /** diff --git a/src/simulation/GroundStation/GroundStation.h b/src/simulation/GroundStation/GroundStation.h index e3060fdcb..a327ba8c2 100644 --- a/src/simulation/GroundStation/GroundStation.h +++ b/src/simulation/GroundStation/GroundStation.h @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h index 553ddca3c..6fba597ee 100644 --- a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h +++ b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h @@ -11,7 +11,7 @@ #include -#include "../../Spacecraft/SampleSpacecraft/SampleSat.h" +#include "../../spacecraft/SampleSpacecraft/SampleSat.h" #include "../GroundStation.h" class SampleGSComponents; diff --git a/src/simulation/Spacecraft/InstalledComponents.cpp b/src/simulation/spacecraft/InstalledComponents.cpp similarity index 100% rename from src/simulation/Spacecraft/InstalledComponents.cpp rename to src/simulation/spacecraft/InstalledComponents.cpp diff --git a/src/simulation/Spacecraft/InstalledComponents.hpp b/src/simulation/spacecraft/InstalledComponents.hpp similarity index 100% rename from src/simulation/Spacecraft/InstalledComponents.hpp rename to src/simulation/spacecraft/InstalledComponents.hpp diff --git a/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp similarity index 100% rename from src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.cpp rename to src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp diff --git a/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h similarity index 98% rename from src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h rename to src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h index 885107af7..29ca3ac0c 100644 --- a/src/simulation/Spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp b/src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp similarity index 100% rename from src/simulation/Spacecraft/SampleSpacecraft/SampleSat.cpp rename to src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp diff --git a/src/simulation/Spacecraft/SampleSpacecraft/SampleSat.h b/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h similarity index 100% rename from src/simulation/Spacecraft/SampleSpacecraft/SampleSat.h rename to src/simulation/spacecraft/SampleSpacecraft/SampleSat.h diff --git a/src/simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h b/src/simulation/spacecraft/SampleSpacecraft/Sample_PortConfig.h similarity index 100% rename from src/simulation/Spacecraft/SampleSpacecraft/Sample_PortConfig.h rename to src/simulation/spacecraft/SampleSpacecraft/Sample_PortConfig.h diff --git a/src/simulation/Spacecraft/Spacecraft.cpp b/src/simulation/spacecraft/Spacecraft.cpp similarity index 100% rename from src/simulation/Spacecraft/Spacecraft.cpp rename to src/simulation/spacecraft/Spacecraft.cpp diff --git a/src/simulation/Spacecraft/Spacecraft.h b/src/simulation/spacecraft/Spacecraft.h similarity index 100% rename from src/simulation/Spacecraft/Spacecraft.h rename to src/simulation/spacecraft/Spacecraft.h diff --git a/src/simulation/Spacecraft/Structure/InitStructure.cpp b/src/simulation/spacecraft/Structure/InitStructure.cpp similarity index 100% rename from src/simulation/Spacecraft/Structure/InitStructure.cpp rename to src/simulation/spacecraft/Structure/InitStructure.cpp diff --git a/src/simulation/Spacecraft/Structure/InitStructure.hpp b/src/simulation/spacecraft/Structure/InitStructure.hpp similarity index 91% rename from src/simulation/Spacecraft/Structure/InitStructure.hpp rename to src/simulation/spacecraft/Structure/InitStructure.hpp index 33eb09615..38f2014b2 100644 --- a/src/simulation/Spacecraft/Structure/InitStructure.hpp +++ b/src/simulation/spacecraft/Structure/InitStructure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitKinematicsParams diff --git a/src/simulation/Spacecraft/Structure/KinematicsParams.cpp b/src/simulation/spacecraft/Structure/KinematicsParams.cpp similarity index 100% rename from src/simulation/Spacecraft/Structure/KinematicsParams.cpp rename to src/simulation/spacecraft/Structure/KinematicsParams.cpp diff --git a/src/simulation/Spacecraft/Structure/KinematicsParams.h b/src/simulation/spacecraft/Structure/KinematicsParams.h similarity index 100% rename from src/simulation/Spacecraft/Structure/KinematicsParams.h rename to src/simulation/spacecraft/Structure/KinematicsParams.h diff --git a/src/simulation/Spacecraft/Structure/RMMParams.cpp b/src/simulation/spacecraft/Structure/RMMParams.cpp similarity index 100% rename from src/simulation/Spacecraft/Structure/RMMParams.cpp rename to src/simulation/spacecraft/Structure/RMMParams.cpp diff --git a/src/simulation/Spacecraft/Structure/RMMParams.h b/src/simulation/spacecraft/Structure/RMMParams.h similarity index 100% rename from src/simulation/Spacecraft/Structure/RMMParams.h rename to src/simulation/spacecraft/Structure/RMMParams.h diff --git a/src/simulation/Spacecraft/Structure/Structure.cpp b/src/simulation/spacecraft/Structure/Structure.cpp similarity index 93% rename from src/simulation/Spacecraft/Structure/Structure.cpp rename to src/simulation/spacecraft/Structure/Structure.cpp index 3f4fd11fb..e1035750b 100644 --- a/src/simulation/Spacecraft/Structure/Structure.cpp +++ b/src/simulation/spacecraft/Structure/Structure.cpp @@ -7,7 +7,7 @@ #include -#include +#include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } diff --git a/src/simulation/Spacecraft/Structure/Structure.h b/src/simulation/spacecraft/Structure/Structure.h similarity index 100% rename from src/simulation/Spacecraft/Structure/Structure.h rename to src/simulation/spacecraft/Structure/Structure.h diff --git a/src/simulation/Spacecraft/Structure/Surface.cpp b/src/simulation/spacecraft/Structure/Surface.cpp similarity index 100% rename from src/simulation/Spacecraft/Structure/Surface.cpp rename to src/simulation/spacecraft/Structure/Surface.cpp diff --git a/src/simulation/Spacecraft/Structure/Surface.h b/src/simulation/spacecraft/Structure/Surface.h similarity index 100% rename from src/simulation/Spacecraft/Structure/Surface.h rename to src/simulation/spacecraft/Structure/Surface.h From 50d0c42c15892270334654858672e290b3afbdf3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:29:57 +0100 Subject: [PATCH 0157/1086] Rename Spacecraft file --- src/simulation/CMakeLists.txt | 2 +- src/simulation/GroundStation/GroundStation.h | 2 +- src/simulation/spacecraft/SampleSpacecraft/SampleSat.h | 2 +- src/simulation/spacecraft/{Spacecraft.cpp => spacecraft.cpp} | 4 ++-- src/simulation/spacecraft/{Spacecraft.h => spacecraft.hpp} | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/spacecraft/{Spacecraft.cpp => spacecraft.cpp} (98%) rename src/simulation/spacecraft/{Spacecraft.h => spacecraft.hpp} (99%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index cae6bef58..88ad9f6fc 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(${PROJECT_NAME} STATIC MCSim/SimulationObject.cpp MCSim/InitMcSim.cpp - spacecraft/Spacecraft.cpp + spacecraft/spacecraft.cpp spacecraft/InstalledComponents.cpp spacecraft/Structure/Structure.cpp spacecraft/Structure/KinematicsParams.cpp diff --git a/src/simulation/GroundStation/GroundStation.h b/src/simulation/GroundStation/GroundStation.h index a327ba8c2..dd8dfdb67 100644 --- a/src/simulation/GroundStation/GroundStation.h +++ b/src/simulation/GroundStation/GroundStation.h @@ -6,10 +6,10 @@ #pragma once #include -#include #include #include +#include #include "../simulation_configuration.hpp" diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h b/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h index 44167ad21..3d3417621 100644 --- a/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h +++ b/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h @@ -5,7 +5,7 @@ #pragma once -#include "../Spacecraft.h" +#include "../spacecraft.hpp" #include "SampleComponents.h" class SampleComponents; diff --git a/src/simulation/spacecraft/Spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp similarity index 98% rename from src/simulation/spacecraft/Spacecraft.cpp rename to src/simulation/spacecraft/spacecraft.cpp index 10da8a52f..697ac8212 100644 --- a/src/simulation/spacecraft/Spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -1,9 +1,9 @@ /** - * @file Spacecraft.cpp + * @file spacecraft.cpp * @brief Definition of Spacecraft class */ -#include "Spacecraft.h" +#include "spacecraft.hpp" #include #include diff --git a/src/simulation/spacecraft/Spacecraft.h b/src/simulation/spacecraft/spacecraft.hpp similarity index 99% rename from src/simulation/spacecraft/Spacecraft.h rename to src/simulation/spacecraft/spacecraft.hpp index 93bcdef5c..f980cf47f 100644 --- a/src/simulation/spacecraft/Spacecraft.h +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -1,5 +1,5 @@ /** - * @file Spacecraft.h + * @file spacecraft.hpp * @brief Definition of Spacecraft class */ From df629008b553068c5046c29c2bd0cdd9d9212aee Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:31:41 +0100 Subject: [PATCH 0158/1086] Fix include guard for spacecraft.hpp --- src/simulation/spacecraft/spacecraft.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index f980cf47f..b39c9d9fb 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -3,7 +3,8 @@ * @brief Definition of Spacecraft class */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ +#define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #include #include @@ -113,3 +114,5 @@ class Spacecraft { InstalledComponents* components_; //!< Components information installed on the spacecraft const int sat_id_; //!< ID of the spacecraft }; + +#endif // S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ From 58f971e87aeb109fbed4f36d06a3c29f172738d5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:34:38 +0100 Subject: [PATCH 0159/1086] Rename InstalledComponents file --- src/simulation/CMakeLists.txt | 2 +- src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- .../{InstalledComponents.cpp => installed_components.cpp} | 4 ++-- .../{InstalledComponents.hpp => installed_components.hpp} | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/spacecraft/{InstalledComponents.cpp => installed_components.cpp} (85%) rename src/simulation/spacecraft/{InstalledComponents.hpp => installed_components.hpp} (97%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 88ad9f6fc..469ec9ffe 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -10,7 +10,7 @@ add_library(${PROJECT_NAME} STATIC MCSim/InitMcSim.cpp spacecraft/spacecraft.cpp - spacecraft/InstalledComponents.cpp + spacecraft/installed_components.cpp spacecraft/Structure/Structure.cpp spacecraft/Structure/KinematicsParams.cpp spacecraft/Structure/RMMParams.cpp diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h index 29ca3ac0c..aeca17422 100644 --- a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h @@ -27,7 +27,7 @@ #include #include -#include "../InstalledComponents.hpp" +#include "../installed_components.hpp" class OBC; class PCU; diff --git a/src/simulation/spacecraft/InstalledComponents.cpp b/src/simulation/spacecraft/installed_components.cpp similarity index 85% rename from src/simulation/spacecraft/InstalledComponents.cpp rename to src/simulation/spacecraft/installed_components.cpp index e6d995e26..ce1118f1b 100644 --- a/src/simulation/spacecraft/InstalledComponents.cpp +++ b/src/simulation/spacecraft/installed_components.cpp @@ -1,9 +1,9 @@ /** - * @file InstalledComponents.cpp + * @file installed_components.cpp * @brief Definition of InstalledComponents class */ -#include "InstalledComponents.hpp" +#include "installed_components.hpp" #include diff --git a/src/simulation/spacecraft/InstalledComponents.hpp b/src/simulation/spacecraft/installed_components.hpp similarity index 97% rename from src/simulation/spacecraft/InstalledComponents.hpp rename to src/simulation/spacecraft/installed_components.hpp index e55f32d3b..4b2f21f77 100644 --- a/src/simulation/spacecraft/InstalledComponents.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -1,5 +1,5 @@ /** - * @file InstalledComponents.hpp + * @file installed_components.hpp * @brief Definition of InstalledComponents class */ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index b39c9d9fb..6aa25ec41 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -12,8 +12,8 @@ #include #include -#include "InstalledComponents.hpp" #include "Structure/Structure.h" +#include "installed_components.hpp" /** * @class Spacecraft From 5e89cf60c9698277b297c72d5ac3a078236c5fea Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:36:22 +0100 Subject: [PATCH 0160/1086] Fix include guard for installed_components.hpp --- src/simulation/spacecraft/installed_components.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index 4b2f21f77..b58a5d46d 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -3,7 +3,9 @@ * @brief Definition of InstalledComponents class */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ +#define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ + #include #include @@ -41,3 +43,5 @@ class InstalledComponents { */ virtual void LogSetup(Logger& logger); }; + +#endif // S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ From 8c212d07ab2f012df1796c7f53c363c3a3ea3f56 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:40:48 +0100 Subject: [PATCH 0161/1086] Rename Structure directory --- src/Component/Propulsion/SimpleThruster.h | 2 +- src/Component/examples/example_change_structure.hpp | 2 +- src/Disturbance/Disturbances.h | 2 +- src/Disturbance/MagDisturbance.h | 2 +- src/Disturbance/SurfaceForce.h | 2 +- src/Dynamics/Dynamics.h | 2 +- src/simulation/CMakeLists.txt | 10 +++++----- .../spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- .../{Structure => structure}/InitStructure.cpp | 0 .../{Structure => structure}/InitStructure.hpp | 2 +- .../{Structure => structure}/KinematicsParams.cpp | 0 .../{Structure => structure}/KinematicsParams.h | 0 .../spacecraft/{Structure => structure}/RMMParams.cpp | 0 .../spacecraft/{Structure => structure}/RMMParams.h | 0 .../spacecraft/{Structure => structure}/Structure.cpp | 2 +- .../spacecraft/{Structure => structure}/Structure.h | 0 .../spacecraft/{Structure => structure}/Surface.cpp | 0 .../spacecraft/{Structure => structure}/Surface.h | 0 19 files changed, 15 insertions(+), 15 deletions(-) rename src/simulation/spacecraft/{Structure => structure}/InitStructure.cpp (100%) rename src/simulation/spacecraft/{Structure => structure}/InitStructure.hpp (91%) rename src/simulation/spacecraft/{Structure => structure}/KinematicsParams.cpp (100%) rename src/simulation/spacecraft/{Structure => structure}/KinematicsParams.h (100%) rename src/simulation/spacecraft/{Structure => structure}/RMMParams.cpp (100%) rename src/simulation/spacecraft/{Structure => structure}/RMMParams.h (100%) rename src/simulation/spacecraft/{Structure => structure}/Structure.cpp (93%) rename src/simulation/spacecraft/{Structure => structure}/Structure.h (100%) rename src/simulation/spacecraft/{Structure => structure}/Surface.cpp (100%) rename src/simulation/spacecraft/{Structure => structure}/Surface.h (100%) diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 075dbba9e..85e95d96e 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -6,7 +6,7 @@ #include #include -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index cecb8b00c..8536b2061 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Disturbance/Disturbances.h b/src/Disturbance/Disturbances.h index 1f54c0455..6d1af4783 100644 --- a/src/Disturbance/Disturbances.h +++ b/src/Disturbance/Disturbances.h @@ -8,7 +8,7 @@ #include #include "../Environment/Global/SimTime.h" -#include "../simulation/spacecraft/Structure/Structure.h" +#include "../simulation/spacecraft/structure/Structure.h" #include "AccelerationDisturbance.h" #include "SimpleDisturbance.h" diff --git a/src/Disturbance/MagDisturbance.h b/src/Disturbance/MagDisturbance.h index d1f83fa97..3fcc7a096 100644 --- a/src/Disturbance/MagDisturbance.h +++ b/src/Disturbance/MagDisturbance.h @@ -12,7 +12,7 @@ using libra::Vector; #include "../Interface/LogOutput/ILoggable.h" -#include "../simulation/spacecraft/Structure/RMMParams.h" +#include "../simulation/spacecraft/structure/RMMParams.h" #include "SimpleDisturbance.h" /** diff --git a/src/Disturbance/SurfaceForce.h b/src/Disturbance/SurfaceForce.h index 66db1d503..a7cee125f 100644 --- a/src/Disturbance/SurfaceForce.h +++ b/src/Disturbance/SurfaceForce.h @@ -10,7 +10,7 @@ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" -#include "../simulation/spacecraft/Structure/Surface.h" +#include "../simulation/spacecraft/structure/Surface.h" #include "SimpleDisturbance.h" using libra::Quaternion; using libra::Vector; diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index 68714834b..38cade82e 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -18,7 +18,7 @@ using libra::Vector; #include "../Environment/Global/SimTime.h" #include "../Environment/Local/LocalCelestialInformation.h" #include "../simulation/simulation_configuration.hpp" -#include "../simulation/spacecraft/Structure/Structure.h" +#include "../simulation/spacecraft/structure/Structure.h" #include "./Orbit/Orbit.h" #include "./Thermal/Temperature.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 469ec9ffe..adb2fbaac 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -11,11 +11,11 @@ add_library(${PROJECT_NAME} STATIC spacecraft/spacecraft.cpp spacecraft/installed_components.cpp - spacecraft/Structure/Structure.cpp - spacecraft/Structure/KinematicsParams.cpp - spacecraft/Structure/RMMParams.cpp - spacecraft/Structure/Surface.cpp - spacecraft/Structure/InitStructure.cpp + spacecraft/structure/Structure.cpp + spacecraft/structure/KinematicsParams.cpp + spacecraft/structure/RMMParams.cpp + spacecraft/structure/Surface.cpp + spacecraft/structure/InitStructure.cpp GroundStation/GroundStation.cpp diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h index aeca17422..8f3b15ad3 100644 --- a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 6aa25ec41..cc5b08fd6 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -12,8 +12,8 @@ #include #include -#include "Structure/Structure.h" #include "installed_components.hpp" +#include "structure/Structure.h" /** * @class Spacecraft diff --git a/src/simulation/spacecraft/Structure/InitStructure.cpp b/src/simulation/spacecraft/structure/InitStructure.cpp similarity index 100% rename from src/simulation/spacecraft/Structure/InitStructure.cpp rename to src/simulation/spacecraft/structure/InitStructure.cpp diff --git a/src/simulation/spacecraft/Structure/InitStructure.hpp b/src/simulation/spacecraft/structure/InitStructure.hpp similarity index 91% rename from src/simulation/spacecraft/Structure/InitStructure.hpp rename to src/simulation/spacecraft/structure/InitStructure.hpp index 38f2014b2..aa87927c5 100644 --- a/src/simulation/spacecraft/Structure/InitStructure.hpp +++ b/src/simulation/spacecraft/structure/InitStructure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitKinematicsParams diff --git a/src/simulation/spacecraft/Structure/KinematicsParams.cpp b/src/simulation/spacecraft/structure/KinematicsParams.cpp similarity index 100% rename from src/simulation/spacecraft/Structure/KinematicsParams.cpp rename to src/simulation/spacecraft/structure/KinematicsParams.cpp diff --git a/src/simulation/spacecraft/Structure/KinematicsParams.h b/src/simulation/spacecraft/structure/KinematicsParams.h similarity index 100% rename from src/simulation/spacecraft/Structure/KinematicsParams.h rename to src/simulation/spacecraft/structure/KinematicsParams.h diff --git a/src/simulation/spacecraft/Structure/RMMParams.cpp b/src/simulation/spacecraft/structure/RMMParams.cpp similarity index 100% rename from src/simulation/spacecraft/Structure/RMMParams.cpp rename to src/simulation/spacecraft/structure/RMMParams.cpp diff --git a/src/simulation/spacecraft/Structure/RMMParams.h b/src/simulation/spacecraft/structure/RMMParams.h similarity index 100% rename from src/simulation/spacecraft/Structure/RMMParams.h rename to src/simulation/spacecraft/structure/RMMParams.h diff --git a/src/simulation/spacecraft/Structure/Structure.cpp b/src/simulation/spacecraft/structure/Structure.cpp similarity index 93% rename from src/simulation/spacecraft/Structure/Structure.cpp rename to src/simulation/spacecraft/structure/Structure.cpp index e1035750b..e460f668a 100644 --- a/src/simulation/spacecraft/Structure/Structure.cpp +++ b/src/simulation/spacecraft/structure/Structure.cpp @@ -7,7 +7,7 @@ #include -#include +#include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } diff --git a/src/simulation/spacecraft/Structure/Structure.h b/src/simulation/spacecraft/structure/Structure.h similarity index 100% rename from src/simulation/spacecraft/Structure/Structure.h rename to src/simulation/spacecraft/structure/Structure.h diff --git a/src/simulation/spacecraft/Structure/Surface.cpp b/src/simulation/spacecraft/structure/Surface.cpp similarity index 100% rename from src/simulation/spacecraft/Structure/Surface.cpp rename to src/simulation/spacecraft/structure/Surface.cpp diff --git a/src/simulation/spacecraft/Structure/Surface.h b/src/simulation/spacecraft/structure/Surface.h similarity index 100% rename from src/simulation/spacecraft/Structure/Surface.h rename to src/simulation/spacecraft/structure/Surface.h From fa7f52685e12dcd9a15ab52625743c6f23e0df47 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:43:18 +0100 Subject: [PATCH 0162/1086] Rename Surface files --- src/Disturbance/SurfaceForce.h | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/spacecraft/structure/Structure.h | 2 +- .../spacecraft/structure/{Surface.cpp => surface.cpp} | 4 ++-- .../spacecraft/structure/{Surface.h => surface.hpp} | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/spacecraft/structure/{Surface.cpp => surface.cpp} (88%) rename src/simulation/spacecraft/structure/{Surface.h => surface.hpp} (99%) diff --git a/src/Disturbance/SurfaceForce.h b/src/Disturbance/SurfaceForce.h index a7cee125f..380381a61 100644 --- a/src/Disturbance/SurfaceForce.h +++ b/src/Disturbance/SurfaceForce.h @@ -10,7 +10,7 @@ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" -#include "../simulation/spacecraft/structure/Surface.h" +#include "../simulation/spacecraft/structure/surface.hpp" #include "SimpleDisturbance.h" using libra::Quaternion; using libra::Vector; diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index adb2fbaac..8b609d4a7 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -14,7 +14,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/structure/Structure.cpp spacecraft/structure/KinematicsParams.cpp spacecraft/structure/RMMParams.cpp - spacecraft/structure/Surface.cpp + spacecraft/structure/surface.cpp spacecraft/structure/InitStructure.cpp GroundStation/GroundStation.cpp diff --git a/src/simulation/spacecraft/structure/Structure.h b/src/simulation/spacecraft/structure/Structure.h index d9c3a6311..c98a40613 100644 --- a/src/simulation/spacecraft/structure/Structure.h +++ b/src/simulation/spacecraft/structure/Structure.h @@ -9,7 +9,7 @@ #include "KinematicsParams.h" #include "RMMParams.h" -#include "Surface.h" +#include "surface.hpp" using std::vector; /** diff --git a/src/simulation/spacecraft/structure/Surface.cpp b/src/simulation/spacecraft/structure/surface.cpp similarity index 88% rename from src/simulation/spacecraft/structure/Surface.cpp rename to src/simulation/spacecraft/structure/surface.cpp index 6268d2ecb..55d96b9d0 100644 --- a/src/simulation/spacecraft/structure/Surface.cpp +++ b/src/simulation/spacecraft/structure/surface.cpp @@ -1,9 +1,9 @@ /** - * @file Surface.cpp + * @file surface.cpp * @brief Definition of spacecraft surface */ -#include "Surface.h" +#include "surface.hpp" Surface::Surface(Vector<3> position, Vector<3> normal, double area, double reflectivity, double specularity, double air_specularity) : position_(position), normal_(normal), area_(area), reflectivity_(reflectivity), specularity_(specularity), air_specularity_(air_specularity) {} diff --git a/src/simulation/spacecraft/structure/Surface.h b/src/simulation/spacecraft/structure/surface.hpp similarity index 99% rename from src/simulation/spacecraft/structure/Surface.h rename to src/simulation/spacecraft/structure/surface.hpp index c2b4927d2..723aa8e9e 100644 --- a/src/simulation/spacecraft/structure/Surface.h +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -1,5 +1,5 @@ /** - * @file Surface.h + * @file surface.hpp * @brief Definition of spacecraft surface */ From 9043a71df8eb86c5801bd3cf807be04a87c9b5a4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:46:00 +0100 Subject: [PATCH 0163/1086] Fix include guard for surface.hpp --- src/simulation/spacecraft/structure/surface.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 723aa8e9e..ca8a8775c 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -3,7 +3,8 @@ * @brief Definition of spacecraft surface */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ #include using libra::Vector; @@ -114,3 +115,5 @@ class Surface { double specularity_; //!< Ratio of specular reflection in the total reflected light double air_specularity_; //!< Specularity for air drag }; + +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ From 1032d8e08437d09e1347874ccab3f63afa474518 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:49:15 +0100 Subject: [PATCH 0164/1086] Rename Structure files --- src/Component/Propulsion/SimpleThruster.h | 2 +- src/Component/examples/example_change_structure.hpp | 3 ++- src/Disturbance/Disturbances.h | 2 +- src/Dynamics/Dynamics.h | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- src/simulation/spacecraft/structure/InitStructure.hpp | 2 +- .../spacecraft/structure/{Structure.cpp => structure.cpp} | 4 ++-- .../spacecraft/structure/{Structure.h => structure.hpp} | 2 +- 10 files changed, 12 insertions(+), 11 deletions(-) rename src/simulation/spacecraft/structure/{Structure.cpp => structure.cpp} (94%) rename src/simulation/spacecraft/structure/{Structure.h => structure.hpp} (98%) diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 85e95d96e..e66a4b712 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -6,11 +6,11 @@ #include #include -#include #include #include #include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 8536b2061..278e65cbd 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -6,7 +6,8 @@ #pragma once #include -#include + +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Disturbance/Disturbances.h b/src/Disturbance/Disturbances.h index 6d1af4783..841d76294 100644 --- a/src/Disturbance/Disturbances.h +++ b/src/Disturbance/Disturbances.h @@ -8,7 +8,7 @@ #include #include "../Environment/Global/SimTime.h" -#include "../simulation/spacecraft/structure/Structure.h" +#include "../simulation/spacecraft/structure/structure.hpp" #include "AccelerationDisturbance.h" #include "SimpleDisturbance.h" diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index 38cade82e..b2a0152a9 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -18,7 +18,7 @@ using libra::Vector; #include "../Environment/Global/SimTime.h" #include "../Environment/Local/LocalCelestialInformation.h" #include "../simulation/simulation_configuration.hpp" -#include "../simulation/spacecraft/structure/Structure.h" +#include "../simulation/spacecraft/structure/structure.hpp" #include "./Orbit/Orbit.h" #include "./Thermal/Temperature.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 8b609d4a7..d939d1a27 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -11,7 +11,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/spacecraft.cpp spacecraft/installed_components.cpp - spacecraft/structure/Structure.cpp + spacecraft/structure/structure.cpp spacecraft/structure/KinematicsParams.cpp spacecraft/structure/RMMParams.cpp spacecraft/structure/surface.cpp diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h index 8f3b15ad3..186c793e6 100644 --- a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h +++ b/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h @@ -8,7 +8,6 @@ #include #include #include -#include #include #include @@ -26,6 +25,7 @@ #include #include #include +#include #include "../installed_components.hpp" diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index cc5b08fd6..2e8f81d22 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -13,7 +13,7 @@ #include #include "installed_components.hpp" -#include "structure/Structure.h" +#include "structure/structure.hpp" /** * @class Spacecraft diff --git a/src/simulation/spacecraft/structure/InitStructure.hpp b/src/simulation/spacecraft/structure/InitStructure.hpp index aa87927c5..614e383d5 100644 --- a/src/simulation/spacecraft/structure/InitStructure.hpp +++ b/src/simulation/spacecraft/structure/InitStructure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitKinematicsParams diff --git a/src/simulation/spacecraft/structure/Structure.cpp b/src/simulation/spacecraft/structure/structure.cpp similarity index 94% rename from src/simulation/spacecraft/structure/Structure.cpp rename to src/simulation/spacecraft/structure/structure.cpp index e460f668a..a18f85136 100644 --- a/src/simulation/spacecraft/structure/Structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -1,9 +1,9 @@ /** - * @file Structure.cpp + * @file structure.cpp * @brief Definition of spacecraft structure */ -#include "Structure.h" +#include "structure.hpp" #include diff --git a/src/simulation/spacecraft/structure/Structure.h b/src/simulation/spacecraft/structure/structure.hpp similarity index 98% rename from src/simulation/spacecraft/structure/Structure.h rename to src/simulation/spacecraft/structure/structure.hpp index c98a40613..7af665d61 100644 --- a/src/simulation/spacecraft/structure/Structure.h +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -1,5 +1,5 @@ /** - * @file Structure.h + * @file structure.hpp * @brief Definition of spacecraft structure */ From 6c660f4b63d8e1916f31c37ad2f57f50ef520657 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:50:25 +0100 Subject: [PATCH 0165/1086] Fix include guard for structure.hpp --- src/simulation/spacecraft/structure/structure.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 7af665d61..c5b767813 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -3,7 +3,9 @@ * @brief Definition of spacecraft structure */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ + #include #include @@ -72,3 +74,5 @@ class Structure { vector surfaces_; //!< Surface information RMMParams* rmm_params_; //!< Residual Magnetic Moment }; + +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ From bf2bd8f79202992415d1d5d7b3287b3a0baaa98a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:56:36 +0100 Subject: [PATCH 0166/1086] Rename RMMParams files --- src/Disturbance/MagDisturbance.h | 2 +- src/simulation/CMakeLists.txt | 2 +- .../{RMMParams.cpp => residual_magnetic_moment.cpp} | 6 +++--- .../structure/{RMMParams.h => residual_magnetic_moment.hpp} | 4 ++-- src/simulation/spacecraft/structure/structure.hpp | 2 +- 5 files changed, 8 insertions(+), 8 deletions(-) rename src/simulation/spacecraft/structure/{RMMParams.cpp => residual_magnetic_moment.cpp} (65%) rename src/simulation/spacecraft/structure/{RMMParams.h => residual_magnetic_moment.hpp} (95%) diff --git a/src/Disturbance/MagDisturbance.h b/src/Disturbance/MagDisturbance.h index 3fcc7a096..9049e5a53 100644 --- a/src/Disturbance/MagDisturbance.h +++ b/src/Disturbance/MagDisturbance.h @@ -12,7 +12,7 @@ using libra::Vector; #include "../Interface/LogOutput/ILoggable.h" -#include "../simulation/spacecraft/structure/RMMParams.h" +#include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "SimpleDisturbance.h" /** diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index d939d1a27..36862b0cb 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -13,7 +13,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/installed_components.cpp spacecraft/structure/structure.cpp spacecraft/structure/KinematicsParams.cpp - spacecraft/structure/RMMParams.cpp + spacecraft/structure/residual_magnetic_moment.cpp spacecraft/structure/surface.cpp spacecraft/structure/InitStructure.cpp diff --git a/src/simulation/spacecraft/structure/RMMParams.cpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp similarity index 65% rename from src/simulation/spacecraft/structure/RMMParams.cpp rename to src/simulation/spacecraft/structure/residual_magnetic_moment.cpp index c79d35e20..365379d38 100644 --- a/src/simulation/spacecraft/structure/RMMParams.cpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp @@ -1,9 +1,9 @@ /** - * @file RMMParams.cpp + * @file residual_magnetic_moment.cpp * @brief Definition of RMM (Residual Magnetic Moment) */ -#include "RMMParams.h" +#include "residual_magnetic_moment.hpp" RMMParams::RMMParams(Vector<3> rmm_const_b, double rmm_rwdev, double rmm_rwlimit, double rmm_wnvar) - : rmm_const_b_(rmm_const_b), rmm_rwdev_(rmm_rwdev), rmm_rwlimit_(rmm_rwlimit), rmm_wnvar_(rmm_wnvar) {} \ No newline at end of file + : rmm_const_b_(rmm_const_b), rmm_rwdev_(rmm_rwdev), rmm_rwlimit_(rmm_rwlimit), rmm_wnvar_(rmm_wnvar) {} diff --git a/src/simulation/spacecraft/structure/RMMParams.h b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp similarity index 95% rename from src/simulation/spacecraft/structure/RMMParams.h rename to src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 9c3fa7a82..dcdf76b36 100644 --- a/src/simulation/spacecraft/structure/RMMParams.h +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -1,6 +1,6 @@ /** - * @file RMMParams.h - * @brief Definition of RMM (Residual Magnetic Moment) + * @file residual_magnetic_moment.hpp + * @brief Definition of Residual Magnetic Moment (RMM) */ #pragma once diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index c5b767813..be599ba48 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -10,7 +10,7 @@ #include #include "KinematicsParams.h" -#include "RMMParams.h" +#include "residual_magnetic_moment.hpp" #include "surface.hpp" using std::vector; From 366ce71faeee4c74ff4379e0167a0643c05e0738 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 09:58:11 +0100 Subject: [PATCH 0167/1086] Fix include guard for residual_magnetic_moment.hpp --- .../spacecraft/structure/residual_magnetic_moment.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index dcdf76b36..5094a9760 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -3,7 +3,9 @@ * @brief Definition of Residual Magnetic Moment (RMM) */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ + #include using libra::Vector; @@ -66,3 +68,5 @@ class RMMParams { double rmm_rwlimit_; //!< Random walk limit of RMM [Am2] double rmm_wnvar_; //!< Standard deviation of white noise of RMM [Am2] }; + +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ \ No newline at end of file From 81cd6f0db5aecbe06a58a6aa9d6c7f5e8f61f8ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:05:45 +0100 Subject: [PATCH 0168/1086] Rename KinematicsParams files --- src/simulation/CMakeLists.txt | 2 +- .../{KinematicsParams.cpp => kinematics_parameters.cpp} | 4 ++-- .../{KinematicsParams.h => kinematics_parameters.hpp} | 2 +- src/simulation/spacecraft/structure/structure.hpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/spacecraft/structure/{KinematicsParams.cpp => kinematics_parameters.cpp} (75%) rename src/simulation/spacecraft/structure/{KinematicsParams.h => kinematics_parameters.hpp} (98%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 36862b0cb..2bd432b5b 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -12,7 +12,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/spacecraft.cpp spacecraft/installed_components.cpp spacecraft/structure/structure.cpp - spacecraft/structure/KinematicsParams.cpp + spacecraft/structure/kinematics_parameters.cpp spacecraft/structure/residual_magnetic_moment.cpp spacecraft/structure/surface.cpp spacecraft/structure/InitStructure.cpp diff --git a/src/simulation/spacecraft/structure/KinematicsParams.cpp b/src/simulation/spacecraft/structure/kinematics_parameters.cpp similarity index 75% rename from src/simulation/spacecraft/structure/KinematicsParams.cpp rename to src/simulation/spacecraft/structure/kinematics_parameters.cpp index fcba6ec73..3200aa0ae 100644 --- a/src/simulation/spacecraft/structure/KinematicsParams.cpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.cpp @@ -1,9 +1,9 @@ /** - * @file KinematicsParams.cpp + * @file kinematics_parameters.cpp * @brief Definition of Kinematics information */ -#include "KinematicsParams.h" +#include "kinematics_parameters.hpp" KinematicsParams::KinematicsParams(Vector<3> cg_b, double mass, Matrix<3, 3> inertia_tensor) : cg_b_(cg_b), mass_(mass), inertia_tensor_(inertia_tensor) {} \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/KinematicsParams.h b/src/simulation/spacecraft/structure/kinematics_parameters.hpp similarity index 98% rename from src/simulation/spacecraft/structure/KinematicsParams.h rename to src/simulation/spacecraft/structure/kinematics_parameters.hpp index 772525814..2544260ae 100644 --- a/src/simulation/spacecraft/structure/KinematicsParams.h +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -1,5 +1,5 @@ /** - * @file KinematicsParams.h + * @file kinematics_parameters.h * @brief Definition of Kinematics information */ diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index be599ba48..3e8412391 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -9,7 +9,7 @@ #include #include -#include "KinematicsParams.h" +#include "kinematics_parameters.hpp" #include "residual_magnetic_moment.hpp" #include "surface.hpp" using std::vector; From 4ef0fb9f12aed2dc70d23c3385f9b60f4eb5f048 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:07:03 +0100 Subject: [PATCH 0169/1086] Fix include guard --- src/simulation/spacecraft/structure/structure.hpp | 6 +++--- src/simulation/spacecraft/structure/surface.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 3e8412391..819251c92 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -3,8 +3,8 @@ * @brief Definition of spacecraft structure */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ #include #include @@ -75,4 +75,4 @@ class Structure { RMMParams* rmm_params_; //!< Residual Magnetic Moment }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index ca8a8775c..8815d6eb8 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -3,8 +3,8 @@ * @brief Definition of spacecraft surface */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ #include using libra::Vector; @@ -116,4 +116,4 @@ class Surface { double air_specularity_; //!< Specularity for air drag }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ From a28ea8496bb1886eb065d1067d02be6b20936b4a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:08:05 +0100 Subject: [PATCH 0170/1086] Fix include guard for kinematics_parameters.hpp --- .../spacecraft/structure/kinematics_parameters.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 2544260ae..7a690df92 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -3,7 +3,8 @@ * @brief Definition of Kinematics information */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ #include #include @@ -84,3 +85,5 @@ class KinematicsParams { double mass_; //!< Mass of the satellite [kg] Matrix<3, 3> inertia_tensor_; //!< Inertia tensor at body frame [kgm2] }; + +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ From 6676c90650138a5ff7969d318f87bbeda51ab9cd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:10:31 +0100 Subject: [PATCH 0171/1086] Rename InitStrucutre files --- src/simulation/CMakeLists.txt | 2 +- .../structure/{InitStructure.cpp => initialize_structure.cpp} | 4 ++-- .../structure/{InitStructure.hpp => initialize_structure.hpp} | 2 +- src/simulation/spacecraft/structure/structure.cpp | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/spacecraft/structure/{InitStructure.cpp => initialize_structure.cpp} (98%) rename src/simulation/spacecraft/structure/{InitStructure.hpp => initialize_structure.hpp} (94%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 2bd432b5b..0bcf7f4cb 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -15,7 +15,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/structure/kinematics_parameters.cpp spacecraft/structure/residual_magnetic_moment.cpp spacecraft/structure/surface.cpp - spacecraft/structure/InitStructure.cpp + spacecraft/structure/initialize_structure.cpp GroundStation/GroundStation.cpp diff --git a/src/simulation/spacecraft/structure/InitStructure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp similarity index 98% rename from src/simulation/spacecraft/structure/InitStructure.cpp rename to src/simulation/spacecraft/structure/initialize_structure.cpp index 2bec77179..5f0d9fa50 100644 --- a/src/simulation/spacecraft/structure/InitStructure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -1,9 +1,9 @@ /** - * @file InitStructure.cpp + * @file initialize_structure.cpp * @brief Initialize functions for spacecraft structure */ -#include "InitStructure.hpp" +#include "initialize_structure.hpp" #include diff --git a/src/simulation/spacecraft/structure/InitStructure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp similarity index 94% rename from src/simulation/spacecraft/structure/InitStructure.hpp rename to src/simulation/spacecraft/structure/initialize_structure.hpp index 614e383d5..e16ce54b3 100644 --- a/src/simulation/spacecraft/structure/InitStructure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -1,5 +1,5 @@ /** - * @file InitStructure.hpp + * @file initialize_structure.hpp * @brief Initialize functions for spacecraft structure */ diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index a18f85136..c5f2acf5f 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -7,7 +7,7 @@ #include -#include +#include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } From 7c004dd0078d292b06dd587ae2a210ef59045f3f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:11:29 +0100 Subject: [PATCH 0172/1086] Fix include guard for initialize_structure.hpp --- src/simulation/spacecraft/structure/initialize_structure.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index e16ce54b3..9849dd84c 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -3,6 +3,9 @@ * @brief Initialize functions for spacecraft structure */ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ + #pragma once #include @@ -22,3 +25,5 @@ vector InitSurfaces(std::string ini_path); * @brief Initialize the RMM(Residual Magnetic Moment) parameters with an ini file */ RMMParams InitRMMParams(std::string ini_path); + +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ From 689f3a7e31ae863783863d067f8fdc2750c78dea Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:13:39 +0100 Subject: [PATCH 0173/1086] Rename SampleSpacecraft directory --- CMakeLists.txt | 4 ++-- src/simulation/Case/SampleCase.cpp | 2 +- src/simulation/Case/SampleCase.h | 2 +- src/simulation/GroundStation/SampleGroundStation/SampleGS.h | 2 +- .../SampleComponents.cpp | 0 .../SampleComponents.h | 0 .../{SampleSpacecraft => sample_spacecraft}/SampleSat.cpp | 0 .../{SampleSpacecraft => sample_spacecraft}/SampleSat.h | 0 .../Sample_PortConfig.h | 0 9 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/spacecraft/{SampleSpacecraft => sample_spacecraft}/SampleComponents.cpp (100%) rename src/simulation/spacecraft/{SampleSpacecraft => sample_spacecraft}/SampleComponents.h (100%) rename src/simulation/spacecraft/{SampleSpacecraft => sample_spacecraft}/SampleSat.cpp (100%) rename src/simulation/spacecraft/{SampleSpacecraft => sample_spacecraft}/SampleSat.h (100%) rename src/simulation/spacecraft/{SampleSpacecraft => sample_spacecraft}/Sample_PortConfig.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5dd5d6018..b81a31e1f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,8 +88,8 @@ add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES src/s2e.cpp src/simulation/Case/SampleCase.cpp - src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp - src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp + src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp + src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp ) diff --git a/src/simulation/Case/SampleCase.cpp b/src/simulation/Case/SampleCase.cpp index 4ee431942..6ac81af26 100644 --- a/src/simulation/Case/SampleCase.cpp +++ b/src/simulation/Case/SampleCase.cpp @@ -5,7 +5,7 @@ #include "SampleCase.h" -#include "../spacecraft/SampleSpacecraft/SampleSat.h" +#include "../spacecraft/sample_spacecraft/SampleSat.h" using std::cout; using std::string; diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h index 16c3146bf..90caff647 100644 --- a/src/simulation/Case/SampleCase.h +++ b/src/simulation/Case/SampleCase.h @@ -6,7 +6,7 @@ #pragma once #include "../GroundStation/SampleGroundStation/SampleGS.h" -#include "../spacecraft/SampleSpacecraft/SampleSat.h" +#include "../spacecraft/sample_spacecraft/SampleSat.h" #include "./SimulationCase.h" /** diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h index 6fba597ee..9d97c058b 100644 --- a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h +++ b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h @@ -11,7 +11,7 @@ #include -#include "../../spacecraft/SampleSpacecraft/SampleSat.h" +#include "../../spacecraft/sample_spacecraft/SampleSat.h" #include "../GroundStation.h" class SampleGSComponents; diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp b/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp similarity index 100% rename from src/simulation/spacecraft/SampleSpacecraft/SampleComponents.cpp rename to src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h b/src/simulation/spacecraft/sample_spacecraft/SampleComponents.h similarity index 100% rename from src/simulation/spacecraft/SampleSpacecraft/SampleComponents.h rename to src/simulation/spacecraft/sample_spacecraft/SampleComponents.h diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp b/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp similarity index 100% rename from src/simulation/spacecraft/SampleSpacecraft/SampleSat.cpp rename to src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp diff --git a/src/simulation/spacecraft/SampleSpacecraft/SampleSat.h b/src/simulation/spacecraft/sample_spacecraft/SampleSat.h similarity index 100% rename from src/simulation/spacecraft/SampleSpacecraft/SampleSat.h rename to src/simulation/spacecraft/sample_spacecraft/SampleSat.h diff --git a/src/simulation/spacecraft/SampleSpacecraft/Sample_PortConfig.h b/src/simulation/spacecraft/sample_spacecraft/Sample_PortConfig.h similarity index 100% rename from src/simulation/spacecraft/SampleSpacecraft/Sample_PortConfig.h rename to src/simulation/spacecraft/sample_spacecraft/Sample_PortConfig.h From e48756731a5b4747309da1b156b7b75a2be085a1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:15:45 +0100 Subject: [PATCH 0174/1086] Rename Sample_PortConfig --- .../spacecraft/sample_spacecraft/SampleComponents.cpp | 2 +- .../{Sample_PortConfig.h => sample_port_configuration.hpp} | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) rename src/simulation/spacecraft/sample_spacecraft/{Sample_PortConfig.h => sample_port_configuration.hpp} (94%) diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp b/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp index 171979077..f961e2a1d 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp @@ -7,7 +7,7 @@ #include -#include "Sample_PortConfig.h" +#include "sample_port_configuration.hpp" SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_env, const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id) diff --git a/src/simulation/spacecraft/sample_spacecraft/Sample_PortConfig.h b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp similarity index 94% rename from src/simulation/spacecraft/sample_spacecraft/Sample_PortConfig.h rename to src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp index c9973c318..87e2f3b4c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/Sample_PortConfig.h +++ b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp @@ -1,5 +1,5 @@ /** - * @file Sample_PortConfig.h + * @file sample_port_configuration.hpp * @brief An example of port configuration management */ From 3515425ae21d4a8158b49c535e2ab0e0080f3f33 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:17:18 +0100 Subject: [PATCH 0175/1086] Fix include guard for sample_port_configuration\.hpp --- .../sample_spacecraft/sample_port_configuration.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp index 87e2f3b4c..2454aa136 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp @@ -3,7 +3,8 @@ * @brief An example of port configuration management */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ /** * @enum PowerPortConfig @@ -25,3 +26,5 @@ enum UARTPortConfig { GYRO = 0, UART_COMPONENT_MAX //!< Maximum port number. Do not remove. Place on the bottom. }; + +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ From c490550d5d3308fcbc84e4a221d257496e0f12c6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:19:54 +0100 Subject: [PATCH 0176/1086] Rename SampleComponents --- CMakeLists.txt | 2 +- src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp | 2 +- src/simulation/spacecraft/sample_spacecraft/SampleSat.h | 2 +- .../{SampleComponents.cpp => sample_components.cpp} | 4 ++-- .../{SampleComponents.h => sample_components.hpp} | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/spacecraft/sample_spacecraft/{SampleComponents.cpp => sample_components.cpp} (99%) rename src/simulation/spacecraft/sample_spacecraft/{SampleComponents.h => sample_components.hpp} (99%) diff --git a/CMakeLists.txt b/CMakeLists.txt index b81a31e1f..e221a03b8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -89,7 +89,7 @@ set(SOURCE_FILES src/s2e.cpp src/simulation/Case/SampleCase.cpp src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp - src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp + src/simulation/spacecraft/sample_spacecraft/sample_components.cpp src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp ) diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp b/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp index 0e4959e8a..ba3fd397a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp @@ -9,7 +9,7 @@ #include -#include "SampleComponents.h" +#include "sample_components.hpp" SampleSat::SampleSat(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : Spacecraft(sim_config, glo_env, sat_id) { sample_components_ = new SampleComponents(dynamics_, structure_, local_env_, glo_env, sim_config, &clock_gen_, sat_id); diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleSat.h b/src/simulation/spacecraft/sample_spacecraft/SampleSat.h index 3d3417621..7871e6c28 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleSat.h +++ b/src/simulation/spacecraft/sample_spacecraft/SampleSat.h @@ -6,7 +6,7 @@ #pragma once #include "../spacecraft.hpp" -#include "SampleComponents.h" +#include "sample_components.hpp" class SampleComponents; diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp similarity index 99% rename from src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp rename to src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index f961e2a1d..8a7c2ebc6 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -1,9 +1,9 @@ /** - * @file SampleComponents.cpp + * @file sample_components.cpp * @brief An example of user side components management installed on a spacecraft */ -#include "SampleComponents.h" +#include "sample_components.hpp" #include diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.h b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp similarity index 99% rename from src/simulation/spacecraft/sample_spacecraft/SampleComponents.h rename to src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 186c793e6..5f6419b0a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleComponents.h +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -1,5 +1,5 @@ /** - * @file SampleComponents.h + * @file sample_components.hpp * @brief An example of user side components management installed on a spacecraft */ From 51c0266be5efb19d814ca7fc487bd11aa5309daf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:20:57 +0100 Subject: [PATCH 0177/1086] Fix include guard for sample_components.hpp --- .../spacecraft/sample_spacecraft/sample_components.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 5f6419b0a..13696b310 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -3,7 +3,9 @@ * @brief An example of user side components management installed on a spacecraft */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ + #include #include #include @@ -116,3 +118,5 @@ class SampleComponents : public InstalledComponents { const LocalEnvironment* local_env_; //!< Local environment information around the spacecraft const GlobalEnvironment* glo_env_; //!< Global environment information }; + +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ From 822c59cb2b60dbeed9f9f5864c81c3d6114f90df Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:25:16 +0100 Subject: [PATCH 0178/1086] Rename SampleSat --- CMakeLists.txt | 2 +- src/simulation/Case/SampleCase.cpp | 2 +- src/simulation/Case/SampleCase.h | 2 +- src/simulation/GroundStation/SampleGroundStation/SampleGS.h | 2 +- .../{SampleSat.cpp => sample_spacecraft.cpp} | 4 ++-- .../sample_spacecraft/{SampleSat.h => sample_spacecraft.hpp} | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) rename src/simulation/spacecraft/sample_spacecraft/{SampleSat.cpp => sample_spacecraft.cpp} (88%) rename src/simulation/spacecraft/sample_spacecraft/{SampleSat.h => sample_spacecraft.hpp} (95%) diff --git a/CMakeLists.txt b/CMakeLists.txt index e221a03b8..44013a2cf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,7 +88,7 @@ add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES src/s2e.cpp src/simulation/Case/SampleCase.cpp - src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp + src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp diff --git a/src/simulation/Case/SampleCase.cpp b/src/simulation/Case/SampleCase.cpp index 6ac81af26..37392d7c4 100644 --- a/src/simulation/Case/SampleCase.cpp +++ b/src/simulation/Case/SampleCase.cpp @@ -5,7 +5,7 @@ #include "SampleCase.h" -#include "../spacecraft/sample_spacecraft/SampleSat.h" +#include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" using std::cout; using std::string; diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h index 90caff647..b2e29ac58 100644 --- a/src/simulation/Case/SampleCase.h +++ b/src/simulation/Case/SampleCase.h @@ -6,7 +6,7 @@ #pragma once #include "../GroundStation/SampleGroundStation/SampleGS.h" -#include "../spacecraft/sample_spacecraft/SampleSat.h" +#include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "./SimulationCase.h" /** diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h index 9d97c058b..b15b46f6c 100644 --- a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h +++ b/src/simulation/GroundStation/SampleGroundStation/SampleGS.h @@ -11,7 +11,7 @@ #include -#include "../../spacecraft/sample_spacecraft/SampleSat.h" +#include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "../GroundStation.h" class SampleGSComponents; diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp similarity index 88% rename from src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp rename to src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index ba3fd397a..847ad0ba5 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleSat.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -1,9 +1,9 @@ /** - * @file SampleSat.cpp + * @file sample_spacecraft.cpp * @brief An example of user side spacecraft class */ -#include "SampleSat.h" +#include "sample_spacecraft.hpp" #include diff --git a/src/simulation/spacecraft/sample_spacecraft/SampleSat.h b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp similarity index 95% rename from src/simulation/spacecraft/sample_spacecraft/SampleSat.h rename to src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index 7871e6c28..35b0dc51f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/SampleSat.h +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -1,5 +1,5 @@ /** - * @file SampleSat.h + * @file sample_spacecraft.hpp * @brief An example of user side spacecraft class */ From 14198e1547accd60c988b296401ce8cdc2e6d3b4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:26:41 +0100 Subject: [PATCH 0179/1086] Fix include guard for sample_spacecraft.hpp --- .../spacecraft/sample_spacecraft/sample_spacecraft.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index 35b0dc51f..0f280c57b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -3,7 +3,8 @@ * @brief An example of user side spacecraft class */ -#pragma once +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ #include "../spacecraft.hpp" #include "sample_components.hpp" @@ -31,3 +32,5 @@ class SampleSat : public Spacecraft { private: SampleComponents* sample_components_; }; + +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ From 374e165df54884a24b1239157f31fd8efdc18e6a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:30:33 +0100 Subject: [PATCH 0180/1086] Rename MCSim directory --- src/Dynamics/Attitude/Attitude.h | 2 +- src/s2e.cpp | 2 +- src/simulation/CMakeLists.txt | 8 ++++---- src/simulation/Case/SimulationCase.h | 2 +- .../{MCSim => monte_carlo_simulation}/InitMcSim.cpp | 0 .../{MCSim => monte_carlo_simulation}/InitMcSim.hpp | 0 .../{MCSim => monte_carlo_simulation}/InitParameter.cpp | 0 .../{MCSim => monte_carlo_simulation}/InitParameter.h | 0 .../{MCSim => monte_carlo_simulation}/MCSimExecutor.cpp | 0 .../{MCSim => monte_carlo_simulation}/MCSimExecutor.h | 0 .../SimulationObject.cpp | 0 .../{MCSim => monte_carlo_simulation}/SimulationObject.h | 0 12 files changed, 7 insertions(+), 7 deletions(-) rename src/simulation/{MCSim => monte_carlo_simulation}/InitMcSim.cpp (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/InitMcSim.hpp (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/InitParameter.cpp (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/InitParameter.h (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/MCSimExecutor.cpp (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/MCSimExecutor.h (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/SimulationObject.cpp (100%) rename src/simulation/{MCSim => monte_carlo_simulation}/SimulationObject.h (100%) diff --git a/src/Dynamics/Attitude/Attitude.h b/src/Dynamics/Attitude/Attitude.h index 48f5253f6..c58cba7e7 100644 --- a/src/Dynamics/Attitude/Attitude.h +++ b/src/Dynamics/Attitude/Attitude.h @@ -6,7 +6,7 @@ #define __attitude_H__ #include -#include +#include #include #include diff --git a/src/s2e.cpp b/src/s2e.cpp index db41ee540..2e1b63418 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -19,7 +19,7 @@ // Add custom include files #include "simulation/Case/SampleCase.h" -// #include "simulation/MCSim/MCSimExecutor.h" +// #include "simulation/monte_carlo_simulation/MCSimExecutor.h" // #include "Interface/HilsInOut/COSMOSWrapper.h" // #include "Interface/HilsInOut/HardwareMessage.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 0bcf7f4cb..93df31527 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -4,10 +4,10 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC Case/SimulationCase.cpp - MCSim/InitParameter.cpp - MCSim/MCSimExecutor.cpp - MCSim/SimulationObject.cpp - MCSim/InitMcSim.cpp + monte_carlo_simulation/InitParameter.cpp + monte_carlo_simulation/MCSimExecutor.cpp + monte_carlo_simulation/SimulationObject.cpp + monte_carlo_simulation/InitMcSim.cpp spacecraft/spacecraft.cpp spacecraft/installed_components.cpp diff --git a/src/simulation/Case/SimulationCase.h b/src/simulation/Case/SimulationCase.h index c3bd3083f..2d5d1dc9d 100644 --- a/src/simulation/Case/SimulationCase.h +++ b/src/simulation/Case/SimulationCase.h @@ -7,7 +7,7 @@ #include #include -#include +#include #include "../simulation_configuration.hpp" class Logger; diff --git a/src/simulation/MCSim/InitMcSim.cpp b/src/simulation/monte_carlo_simulation/InitMcSim.cpp similarity index 100% rename from src/simulation/MCSim/InitMcSim.cpp rename to src/simulation/monte_carlo_simulation/InitMcSim.cpp diff --git a/src/simulation/MCSim/InitMcSim.hpp b/src/simulation/monte_carlo_simulation/InitMcSim.hpp similarity index 100% rename from src/simulation/MCSim/InitMcSim.hpp rename to src/simulation/monte_carlo_simulation/InitMcSim.hpp diff --git a/src/simulation/MCSim/InitParameter.cpp b/src/simulation/monte_carlo_simulation/InitParameter.cpp similarity index 100% rename from src/simulation/MCSim/InitParameter.cpp rename to src/simulation/monte_carlo_simulation/InitParameter.cpp diff --git a/src/simulation/MCSim/InitParameter.h b/src/simulation/monte_carlo_simulation/InitParameter.h similarity index 100% rename from src/simulation/MCSim/InitParameter.h rename to src/simulation/monte_carlo_simulation/InitParameter.h diff --git a/src/simulation/MCSim/MCSimExecutor.cpp b/src/simulation/monte_carlo_simulation/MCSimExecutor.cpp similarity index 100% rename from src/simulation/MCSim/MCSimExecutor.cpp rename to src/simulation/monte_carlo_simulation/MCSimExecutor.cpp diff --git a/src/simulation/MCSim/MCSimExecutor.h b/src/simulation/monte_carlo_simulation/MCSimExecutor.h similarity index 100% rename from src/simulation/MCSim/MCSimExecutor.h rename to src/simulation/monte_carlo_simulation/MCSimExecutor.h diff --git a/src/simulation/MCSim/SimulationObject.cpp b/src/simulation/monte_carlo_simulation/SimulationObject.cpp similarity index 100% rename from src/simulation/MCSim/SimulationObject.cpp rename to src/simulation/monte_carlo_simulation/SimulationObject.cpp diff --git a/src/simulation/MCSim/SimulationObject.h b/src/simulation/monte_carlo_simulation/SimulationObject.h similarity index 100% rename from src/simulation/MCSim/SimulationObject.h rename to src/simulation/monte_carlo_simulation/SimulationObject.h From 1adf8516a72803b6e0663e8e7a58f016c9b65ad3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:34:37 +0100 Subject: [PATCH 0181/1086] Rename SimulationObject --- src/Dynamics/Attitude/Attitude.h | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/monte_carlo_simulation/MCSimExecutor.h | 2 +- .../{SimulationObject.cpp => simulation_object.cpp} | 4 ++-- .../{SimulationObject.h => simulation_object.hpp} | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/monte_carlo_simulation/{SimulationObject.cpp => simulation_object.cpp} (96%) rename src/simulation/monte_carlo_simulation/{SimulationObject.h => simulation_object.hpp} (98%) diff --git a/src/Dynamics/Attitude/Attitude.h b/src/Dynamics/Attitude/Attitude.h index c58cba7e7..13b862968 100644 --- a/src/Dynamics/Attitude/Attitude.h +++ b/src/Dynamics/Attitude/Attitude.h @@ -6,10 +6,10 @@ #define __attitude_H__ #include -#include #include #include +#include #include /** diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 93df31527..070cb05af 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC monte_carlo_simulation/InitParameter.cpp monte_carlo_simulation/MCSimExecutor.cpp - monte_carlo_simulation/SimulationObject.cpp + monte_carlo_simulation/simulation_object.cpp monte_carlo_simulation/InitMcSim.cpp spacecraft/spacecraft.cpp diff --git a/src/simulation/monte_carlo_simulation/MCSimExecutor.h b/src/simulation/monte_carlo_simulation/MCSimExecutor.h index 3369b208e..bc8f7940c 100644 --- a/src/simulation/monte_carlo_simulation/MCSimExecutor.h +++ b/src/simulation/monte_carlo_simulation/MCSimExecutor.h @@ -8,7 +8,7 @@ #include #include #include -//#include "SimulationObject.h" +// #include "simulation_object.hpp" #include "InitParameter.h" using libra::Vector; diff --git a/src/simulation/monte_carlo_simulation/SimulationObject.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp similarity index 96% rename from src/simulation/monte_carlo_simulation/SimulationObject.cpp rename to src/simulation/monte_carlo_simulation/simulation_object.cpp index 599dca9e3..464d8fd90 100644 --- a/src/simulation/monte_carlo_simulation/SimulationObject.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -1,9 +1,9 @@ /** - * @file SimulationObject.cpp + * @file simulation_object.cpp * @brief Class to manage randomization of variables for Monte-Carlo simulation */ -#include "SimulationObject.h" +#include "simulation_object.hpp" std::map SimulationObject::so_list_; diff --git a/src/simulation/monte_carlo_simulation/SimulationObject.h b/src/simulation/monte_carlo_simulation/simulation_object.hpp similarity index 98% rename from src/simulation/monte_carlo_simulation/SimulationObject.h rename to src/simulation/monte_carlo_simulation/simulation_object.hpp index 0ecdf6c9b..4f027c212 100644 --- a/src/simulation/monte_carlo_simulation/SimulationObject.h +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -1,5 +1,5 @@ /** - * @file SimulationObject.h + * @file simulation_object.h * @brief Class to manage randomization of variables for Monte-Carlo simulation */ From 7d84f56c0e1d5161799e16e993374d26108a0341 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 10:36:11 +0100 Subject: [PATCH 0182/1086] Fix include guard for simulation_object.hpp --- src/simulation/monte_carlo_simulation/simulation_object.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 4f027c212..ece595b33 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -3,7 +3,8 @@ * @brief Class to manage randomization of variables for Monte-Carlo simulation */ -#pragma once +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ #include #include @@ -79,3 +80,5 @@ template void SimulationObject::GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, Vector& dst_vec) const { mc_sim.GetInitParameterVec(name_, ip_name, dst_vec); } + +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ From eb748a06ea646aa4aed632c63b2508605dc38a99 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:02:01 +0100 Subject: [PATCH 0183/1086] Rename MCSimExecutor --- src/s2e.cpp | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/Case/SimulationCase.h | 3 ++- src/simulation/monte_carlo_simulation/InitMcSim.hpp | 2 +- ...{MCSimExecutor.cpp => monte_carlo_simulation_executor.cpp} | 4 ++-- .../{MCSimExecutor.h => monte_carlo_simulation_executor.hpp} | 2 +- src/simulation/monte_carlo_simulation/simulation_object.hpp | 2 +- 7 files changed, 9 insertions(+), 8 deletions(-) rename src/simulation/monte_carlo_simulation/{MCSimExecutor.cpp => monte_carlo_simulation_executor.cpp} (95%) rename src/simulation/monte_carlo_simulation/{MCSimExecutor.h => monte_carlo_simulation_executor.hpp} (99%) diff --git a/src/s2e.cpp b/src/s2e.cpp index 2e1b63418..3bfa934a5 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -19,7 +19,7 @@ // Add custom include files #include "simulation/Case/SampleCase.h" -// #include "simulation/monte_carlo_simulation/MCSimExecutor.h" +// #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" // #include "Interface/HilsInOut/COSMOSWrapper.h" // #include "Interface/HilsInOut/HardwareMessage.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 070cb05af..32c8f3563 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC Case/SimulationCase.cpp monte_carlo_simulation/InitParameter.cpp - monte_carlo_simulation/MCSimExecutor.cpp + monte_carlo_simulation/monte_carlo_simulation_executor.cpp monte_carlo_simulation/simulation_object.cpp monte_carlo_simulation/InitMcSim.cpp diff --git a/src/simulation/Case/SimulationCase.h b/src/simulation/Case/SimulationCase.h index 2d5d1dc9d..3ea3d4cd0 100644 --- a/src/simulation/Case/SimulationCase.h +++ b/src/simulation/Case/SimulationCase.h @@ -7,7 +7,8 @@ #include #include -#include + +#include #include "../simulation_configuration.hpp" class Logger; diff --git a/src/simulation/monte_carlo_simulation/InitMcSim.hpp b/src/simulation/monte_carlo_simulation/InitMcSim.hpp index 024cb5e3b..be8a3b73a 100644 --- a/src/simulation/monte_carlo_simulation/InitMcSim.hpp +++ b/src/simulation/monte_carlo_simulation/InitMcSim.hpp @@ -6,7 +6,7 @@ #pragma once #include "InitParameter.h" -#include "MCSimExecutor.h" +#include "monte_carlo_simulation_executor.hpp" /** * @fn InitMCSim diff --git a/src/simulation/monte_carlo_simulation/MCSimExecutor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp similarity index 95% rename from src/simulation/monte_carlo_simulation/MCSimExecutor.cpp rename to src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 2ef9fb92d..4ca123337 100644 --- a/src/simulation/monte_carlo_simulation/MCSimExecutor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -1,9 +1,9 @@ /** - * @file MCSimExecutor.cpp + * @file monte_carlo_simulation_executor.cpp * @brief Monte-Carlo Simulation Executor class */ -#include "MCSimExecutor.h" +#include "monte_carlo_simulation_executor.hpp" using std::string; diff --git a/src/simulation/monte_carlo_simulation/MCSimExecutor.h b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp similarity index 99% rename from src/simulation/monte_carlo_simulation/MCSimExecutor.h rename to src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index bc8f7940c..39d6fb53e 100644 --- a/src/simulation/monte_carlo_simulation/MCSimExecutor.h +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -1,5 +1,5 @@ /** - * @file MCSimExecutor.h + * @file monte_carlo_simulation_executor.hpp * @brief Monte-Carlo Simulation Executor class */ diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index ece595b33..58c021673 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -14,7 +14,7 @@ #include #include "InitParameter.h" -#include "MCSimExecutor.h" +#include "monte_carlo_simulation_executor.hpp" using libra::Vector; From 6c5defee1d4ed87415c1ec5a047aea4a37c7cdf1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:03:46 +0100 Subject: [PATCH 0184/1086] Fix include guard for monte_carlo_simulation_executor.hpp --- .../monte_carlo_simulation_executor.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 39d6fb53e..8e6979a02 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -3,7 +3,8 @@ * @brief Monte-Carlo Simulation Executor class */ -#pragma once +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ #include #include @@ -174,3 +175,5 @@ void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, c throw "More than one definition of one InitParameter."; } } + +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ From 6c4164cb580d2a9ef3e958ecfeee893d850d2832 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:09:34 +0100 Subject: [PATCH 0185/1086] Rename InitParams --- src/simulation/CMakeLists.txt | 2 +- src/simulation/monte_carlo_simulation/InitMcSim.hpp | 2 +- ...nitParameter.cpp => initialize_monte_carlo_parameters.cpp} | 4 ++-- ...{InitParameter.h => initialize_monte_carlo_parameters.hpp} | 2 +- .../monte_carlo_simulation_executor.hpp | 2 +- src/simulation/monte_carlo_simulation/simulation_object.hpp | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) rename src/simulation/monte_carlo_simulation/{InitParameter.cpp => initialize_monte_carlo_parameters.cpp} (99%) rename src/simulation/monte_carlo_simulation/{InitParameter.h => initialize_monte_carlo_parameters.hpp} (99%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 32c8f3563..2626b5b3d 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC Case/SimulationCase.cpp - monte_carlo_simulation/InitParameter.cpp + monte_carlo_simulation/initialize_monte_carlo_parameters.cpp monte_carlo_simulation/monte_carlo_simulation_executor.cpp monte_carlo_simulation/simulation_object.cpp monte_carlo_simulation/InitMcSim.cpp diff --git a/src/simulation/monte_carlo_simulation/InitMcSim.hpp b/src/simulation/monte_carlo_simulation/InitMcSim.hpp index be8a3b73a..b1b0a8ef5 100644 --- a/src/simulation/monte_carlo_simulation/InitMcSim.hpp +++ b/src/simulation/monte_carlo_simulation/InitMcSim.hpp @@ -5,7 +5,7 @@ #pragma once -#include "InitParameter.h" +#include "initialize_monte_carlo_parameters.hpp" #include "monte_carlo_simulation_executor.hpp" /** diff --git a/src/simulation/monte_carlo_simulation/InitParameter.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp similarity index 99% rename from src/simulation/monte_carlo_simulation/InitParameter.cpp rename to src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 1fa396198..1849cf560 100644 --- a/src/simulation/monte_carlo_simulation/InitParameter.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -1,9 +1,9 @@ /** - * @file InitParameter.cpp + * @file initialize_monte_carlo_parameters.cpp * @brief Initialized parameters for Monte-Carlo simulation */ -#include "InitParameter.h" +#include "initialize_monte_carlo_parameters.hpp" #include diff --git a/src/simulation/monte_carlo_simulation/InitParameter.h b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp similarity index 99% rename from src/simulation/monte_carlo_simulation/InitParameter.h rename to src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index f2a2f2d2e..8e5daca40 100644 --- a/src/simulation/monte_carlo_simulation/InitParameter.h +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -1,5 +1,5 @@ /** - * @file InitParameter.h + * @file initialize_monte_carlo_parameters.h * @brief Initialized parameters for Monte-Carlo simulation */ diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 8e6979a02..b737aeaeb 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -10,7 +10,7 @@ #include #include // #include "simulation_object.hpp" -#include "InitParameter.h" +#include "initialize_monte_carlo_parameters.hpp" using libra::Vector; diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 58c021673..13016b515 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -13,7 +13,7 @@ #include #include -#include "InitParameter.h" +#include "initialize_monte_carlo_parameters.hpp" #include "monte_carlo_simulation_executor.hpp" using libra::Vector; From a8d1ff8e89126ec80030029de5e5c1441b9ed812 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:11:04 +0100 Subject: [PATCH 0186/1086] Fix include guard for initialize_monte_carlo_parameters.hpp --- .../initialize_monte_carlo_parameters.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 8e5daca40..8ad546f0c 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -3,7 +3,8 @@ * @brief Initialized parameters for Monte-Carlo simulation */ -#pragma once +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ #include #include @@ -231,3 +232,5 @@ void InitParameter::GetVec(Vector& dst_vec) const { } } } + +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ From 27d4f360bb09ea5102bf9fa4eda0115289daaffe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:13:34 +0100 Subject: [PATCH 0187/1086] Rename InitMCSim --- src/simulation/CMakeLists.txt | 4 ++-- .../{InitMcSim.cpp => initialize_monte_carlo_simulation.cpp} | 4 ++-- .../{InitMcSim.hpp => initialize_monte_carlo_simulation.hpp} | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/monte_carlo_simulation/{InitMcSim.cpp => initialize_monte_carlo_simulation.cpp} (97%) rename src/simulation/monte_carlo_simulation/{InitMcSim.hpp => initialize_monte_carlo_simulation.hpp} (86%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 2626b5b3d..e123ca0d9 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -4,10 +4,10 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC Case/SimulationCase.cpp - monte_carlo_simulation/initialize_monte_carlo_parameters.cpp monte_carlo_simulation/monte_carlo_simulation_executor.cpp monte_carlo_simulation/simulation_object.cpp - monte_carlo_simulation/InitMcSim.cpp + monte_carlo_simulation/initialize_monte_carlo_parameters.cpp + monte_carlo_simulation/initialize_monte_carlo_simulation.cpp spacecraft/spacecraft.cpp spacecraft/installed_components.cpp diff --git a/src/simulation/monte_carlo_simulation/InitMcSim.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp similarity index 97% rename from src/simulation/monte_carlo_simulation/InitMcSim.cpp rename to src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 50429dd2e..4538d170d 100644 --- a/src/simulation/monte_carlo_simulation/InitMcSim.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -1,9 +1,9 @@ /** - * @file InitMcSim.cpp + * @file initialize_monte_carlo_simulation.cpp * @brief Initialize function for Monte-Carlo Simulator */ -#include "InitMcSim.hpp" +#include "initialize_monte_carlo_simulation.hpp" #include diff --git a/src/simulation/monte_carlo_simulation/InitMcSim.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp similarity index 86% rename from src/simulation/monte_carlo_simulation/InitMcSim.hpp rename to src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp index b1b0a8ef5..dd7f8b6b8 100644 --- a/src/simulation/monte_carlo_simulation/InitMcSim.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp @@ -1,5 +1,5 @@ /** - * @file InitMcSim.hpp + * @file initialize_monte_carlo_simulation.hpp * @brief Initialize function for Monte-Carlo Simulator */ From 30a5ea1797a03e3b5e0acacbccdfc42e1d486963 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:14:32 +0100 Subject: [PATCH 0188/1086] Fix include guard for initialize_monte_carlo_simulation.hpp --- .../initialize_monte_carlo_simulation.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp index dd7f8b6b8..e53d061a7 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp @@ -3,7 +3,8 @@ * @brief Initialize function for Monte-Carlo Simulator */ -#pragma once +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ #include "initialize_monte_carlo_parameters.hpp" #include "monte_carlo_simulation_executor.hpp" @@ -13,3 +14,5 @@ * @brief Initialize function for Monte-Carlo Simulator */ MCSimExecutor* InitMCSim(std::string file_name); + +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ From e4d63d4b03bca721e830adc501ba6c2741ee67c6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:18:40 +0100 Subject: [PATCH 0189/1086] Rename and fix InterSatComm --- src/simulation/CMakeLists.txt | 2 +- .../inter_spacecraft_communication.cpp} | 4 ++-- .../inter_spacecraft_communication.hpp} | 9 ++++++--- 3 files changed, 9 insertions(+), 6 deletions(-) rename src/simulation/{InterSatComm/InterSatComm.cpp => inter_spacecraft_communication/inter_spacecraft_communication.cpp} (71%) rename src/simulation/{InterSatComm/InterSatComm.h => inter_spacecraft_communication/inter_spacecraft_communication.hpp} (57%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index e123ca0d9..256e5440f 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -19,7 +19,7 @@ add_library(${PROJECT_NAME} STATIC GroundStation/GroundStation.cpp - InterSatComm/InterSatComm.cpp + inter_spacecraft_communication/inter_spacecraft_communication.cpp ) include(../../common.cmake) diff --git a/src/simulation/InterSatComm/InterSatComm.cpp b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp similarity index 71% rename from src/simulation/InterSatComm/InterSatComm.cpp rename to src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp index 5f13585fc..ca2142f50 100644 --- a/src/simulation/InterSatComm/InterSatComm.cpp +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp @@ -1,9 +1,9 @@ /** - * @file InterSatComm.cpp + * @file inter_spacecraft_communication.cpp * @brief Base class of inter satellite communication */ -#include "InterSatComm.h" +#include "inter_spacecraft_communication.hpp" #include diff --git a/src/simulation/InterSatComm/InterSatComm.h b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp similarity index 57% rename from src/simulation/InterSatComm/InterSatComm.h rename to src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp index 04aa4f737..3a0cbeb6f 100644 --- a/src/simulation/InterSatComm/InterSatComm.h +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp @@ -1,9 +1,10 @@ /** - * @file InterSatComm.h + * @file inter_spacecraft_communication.h * @brief Base class of inter satellite communication */ -#pragma once +#ifndef S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ +#define S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ #include "../simulation_configuration.hpp" @@ -25,4 +26,6 @@ class InterSatComm { ~InterSatComm(); private: -}; \ No newline at end of file +}; + +#endif // S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ From b274f6a331820935e5fdef19b250947235eb20ad Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:20:59 +0100 Subject: [PATCH 0190/1086] Rename GroundStation directory --- CMakeLists.txt | 4 ++-- src/Component/CommGS/GScalculator.h | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/Case/SampleCase.h | 2 +- .../{GroundStation => ground_station}/GroundStation.cpp | 0 .../{GroundStation => ground_station}/GroundStation.h | 0 .../SampleGroundStation/SampleGS.cpp | 0 .../SampleGroundStation/SampleGS.h | 0 .../SampleGroundStation/SampleGSComponents.cpp | 0 .../SampleGroundStation/SampleGSComponents.h | 0 10 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/{GroundStation => ground_station}/GroundStation.cpp (100%) rename src/simulation/{GroundStation => ground_station}/GroundStation.h (100%) rename src/simulation/{GroundStation => ground_station}/SampleGroundStation/SampleGS.cpp (100%) rename src/simulation/{GroundStation => ground_station}/SampleGroundStation/SampleGS.h (100%) rename src/simulation/{GroundStation => ground_station}/SampleGroundStation/SampleGSComponents.cpp (100%) rename src/simulation/{GroundStation => ground_station}/SampleGroundStation/SampleGSComponents.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 44013a2cf..8a5b182b6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,8 +90,8 @@ set(SOURCE_FILES src/simulation/Case/SampleCase.cpp src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp - src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp - src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp + src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp + src/simulation/ground_station/SampleGroundStation/SampleGS.cpp ) ## Create executable file diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index bb144920b..3637b0f41 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 256e5440f..ebf9208a7 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -17,7 +17,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/structure/surface.cpp spacecraft/structure/initialize_structure.cpp - GroundStation/GroundStation.cpp + ground_station/GroundStation.cpp inter_spacecraft_communication/inter_spacecraft_communication.cpp ) diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h index b2e29ac58..2723e42e1 100644 --- a/src/simulation/Case/SampleCase.h +++ b/src/simulation/Case/SampleCase.h @@ -5,7 +5,7 @@ #pragma once -#include "../GroundStation/SampleGroundStation/SampleGS.h" +#include "../ground_station/SampleGroundStation/SampleGS.h" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "./SimulationCase.h" diff --git a/src/simulation/GroundStation/GroundStation.cpp b/src/simulation/ground_station/GroundStation.cpp similarity index 100% rename from src/simulation/GroundStation/GroundStation.cpp rename to src/simulation/ground_station/GroundStation.cpp diff --git a/src/simulation/GroundStation/GroundStation.h b/src/simulation/ground_station/GroundStation.h similarity index 100% rename from src/simulation/GroundStation/GroundStation.h rename to src/simulation/ground_station/GroundStation.h diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp b/src/simulation/ground_station/SampleGroundStation/SampleGS.cpp similarity index 100% rename from src/simulation/GroundStation/SampleGroundStation/SampleGS.cpp rename to src/simulation/ground_station/SampleGroundStation/SampleGS.cpp diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGS.h b/src/simulation/ground_station/SampleGroundStation/SampleGS.h similarity index 100% rename from src/simulation/GroundStation/SampleGroundStation/SampleGS.h rename to src/simulation/ground_station/SampleGroundStation/SampleGS.h diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp b/src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp similarity index 100% rename from src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.cpp rename to src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp diff --git a/src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.h b/src/simulation/ground_station/SampleGroundStation/SampleGSComponents.h similarity index 100% rename from src/simulation/GroundStation/SampleGroundStation/SampleGSComponents.h rename to src/simulation/ground_station/SampleGroundStation/SampleGSComponents.h From 8f9027a11aa7344aae5eaf380de1f23d89dd8865 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:23:05 +0100 Subject: [PATCH 0191/1086] Rename GroundStation files --- src/Component/CommGS/GScalculator.h | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/ground_station/SampleGroundStation/SampleGS.h | 2 +- .../ground_station/{GroundStation.cpp => ground_station.cpp} | 4 ++-- .../ground_station/{GroundStation.h => ground_station.hpp} | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/simulation/ground_station/{GroundStation.cpp => ground_station.cpp} (98%) rename src/simulation/ground_station/{GroundStation.h => ground_station.hpp} (99%) diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 3637b0f41..10bf0c66c 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -8,12 +8,12 @@ #include #include #include -#include #include #include #include #include +#include using libra::Matrix; using libra::Vector; diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index ebf9208a7..8f42aa27c 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -17,7 +17,7 @@ add_library(${PROJECT_NAME} STATIC spacecraft/structure/surface.cpp spacecraft/structure/initialize_structure.cpp - ground_station/GroundStation.cpp + ground_station/ground_station.cpp inter_spacecraft_communication/inter_spacecraft_communication.cpp ) diff --git a/src/simulation/ground_station/SampleGroundStation/SampleGS.h b/src/simulation/ground_station/SampleGroundStation/SampleGS.h index b15b46f6c..f95513651 100644 --- a/src/simulation/ground_station/SampleGroundStation/SampleGS.h +++ b/src/simulation/ground_station/SampleGroundStation/SampleGS.h @@ -12,7 +12,7 @@ #include #include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" -#include "../GroundStation.h" +#include "../ground_station.hpp" class SampleGSComponents; diff --git a/src/simulation/ground_station/GroundStation.cpp b/src/simulation/ground_station/ground_station.cpp similarity index 98% rename from src/simulation/ground_station/GroundStation.cpp rename to src/simulation/ground_station/ground_station.cpp index fabe46ec0..48083c95f 100644 --- a/src/simulation/ground_station/GroundStation.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -1,9 +1,9 @@ /** - * @file GroundStation.cpp + * @file ground_station.cpp * @brief Base class of ground station */ -#include "GroundStation.h" +#include "ground_station.hpp" #include #include diff --git a/src/simulation/ground_station/GroundStation.h b/src/simulation/ground_station/ground_station.hpp similarity index 99% rename from src/simulation/ground_station/GroundStation.h rename to src/simulation/ground_station/ground_station.hpp index dd8dfdb67..fc251f962 100644 --- a/src/simulation/ground_station/GroundStation.h +++ b/src/simulation/ground_station/ground_station.hpp @@ -1,5 +1,5 @@ /** - * @file GroundStation.h + * @file ground_station.h * @brief Base class of ground station */ From 383ab2420cec2fce873bced2854f16b93ac7d216 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:24:43 +0100 Subject: [PATCH 0192/1086] Fix include guard for ground_station.hpp --- src/simulation/ground_station/ground_station.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index fc251f962..a2e0b220d 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -3,7 +3,8 @@ * @brief Base class of ground station */ -#pragma once +#ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ +#define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #include @@ -109,3 +110,5 @@ class GroundStation : public ILoggable { */ bool CalcIsVisible(const Vector<3> sc_pos_ecef_m); }; + +#endif // S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ From dbc002a5bf871ad95442caf811cef44814690d7d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:29:18 +0100 Subject: [PATCH 0193/1086] Rename SampleGs --- .../SampleGSComponents.cpp | 0 .../SampleGSComponents.h | 0 .../sample_ground_station.cpp} | 0 .../sample_ground_station.hpp} | 0 4 files changed, 0 insertions(+), 0 deletions(-) rename src/simulation/ground_station/{SampleGroundStation => sample_ground_station}/SampleGSComponents.cpp (100%) rename src/simulation/ground_station/{SampleGroundStation => sample_ground_station}/SampleGSComponents.h (100%) rename src/simulation/ground_station/{SampleGroundStation/SampleGS.cpp => sample_ground_station/sample_ground_station.cpp} (100%) rename src/simulation/ground_station/{SampleGroundStation/SampleGS.h => sample_ground_station/sample_ground_station.hpp} (100%) diff --git a/src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp b/src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp similarity index 100% rename from src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp rename to src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp diff --git a/src/simulation/ground_station/SampleGroundStation/SampleGSComponents.h b/src/simulation/ground_station/sample_ground_station/SampleGSComponents.h similarity index 100% rename from src/simulation/ground_station/SampleGroundStation/SampleGSComponents.h rename to src/simulation/ground_station/sample_ground_station/SampleGSComponents.h diff --git a/src/simulation/ground_station/SampleGroundStation/SampleGS.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp similarity index 100% rename from src/simulation/ground_station/SampleGroundStation/SampleGS.cpp rename to src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp diff --git a/src/simulation/ground_station/SampleGroundStation/SampleGS.h b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp similarity index 100% rename from src/simulation/ground_station/SampleGroundStation/SampleGS.h rename to src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp From 53dcc6c95be00bccb9c73555e3c4fa776ae6b845 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:30:32 +0100 Subject: [PATCH 0194/1086] Rename SampleGs --- CMakeLists.txt | 4 ++-- src/simulation/Case/SampleCase.h | 2 +- .../sample_ground_station/sample_ground_station.cpp | 4 ++-- .../sample_ground_station/sample_ground_station.hpp | 7 +++++-- 4 files changed, 10 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8a5b182b6..8af794baf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,8 +90,8 @@ set(SOURCE_FILES src/simulation/Case/SampleCase.cpp src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp - src/simulation/ground_station/SampleGroundStation/SampleGSComponents.cpp - src/simulation/ground_station/SampleGroundStation/SampleGS.cpp + src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp + src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp ) ## Create executable file diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/Case/SampleCase.h index 2723e42e1..74f4fe835 100644 --- a/src/simulation/Case/SampleCase.h +++ b/src/simulation/Case/SampleCase.h @@ -5,7 +5,7 @@ #pragma once -#include "../ground_station/SampleGroundStation/SampleGS.h" +#include "../ground_station/sample_ground_station/sample_ground_station.hpp" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "./SimulationCase.h" diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index c34b63cf1..c692de197 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -1,9 +1,9 @@ /** - * @file SampleGS.cpp + * @file sample_ground_station.cpp * @brief An example of user defined ground station class */ -#include "SampleGS.h" +#include "sample_ground_station.hpp" #include "SampleGSComponents.h" diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index f95513651..6c34c485c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -1,9 +1,10 @@ /** - * @file SampleGS.h + * @file sample_ground_station.h * @brief An example of user defined ground station class */ -#pragma once +#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ +#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #include #include @@ -52,3 +53,5 @@ class SampleGS : public GroundStation { private: SampleGSComponents* components_; //!< Ground station related components }; + +#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ From de6ab360f70a91a82427d513c28360d3a7216fca Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:33:23 +0100 Subject: [PATCH 0195/1086] Rename SampleGsComponents --- CMakeLists.txt | 2 +- .../sample_ground_station/sample_ground_station.cpp | 2 +- ...Components.cpp => sample_ground_station_components.cpp} | 4 ++-- ...GSComponents.h => sample_ground_station_components.hpp} | 7 +++++-- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/simulation/ground_station/sample_ground_station/{SampleGSComponents.cpp => sample_ground_station_components.cpp} (91%) rename src/simulation/ground_station/sample_ground_station/{SampleGSComponents.h => sample_ground_station_components.hpp} (77%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8af794baf..636b62562 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,7 +90,7 @@ set(SOURCE_FILES src/simulation/Case/SampleCase.cpp src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp - src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp + src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp ) diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index c692de197..d76257c6c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -5,7 +5,7 @@ #include "sample_ground_station.hpp" -#include "SampleGSComponents.h" +#include "sample_ground_station_components.hpp" SampleGS::SampleGS(SimulationConfig* config, int gs_id) : GroundStation(config, gs_id) { Initialize(config); } diff --git a/src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp similarity index 91% rename from src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp rename to src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index cd983d49f..00f52406a 100644 --- a/src/simulation/ground_station/sample_ground_station/SampleGSComponents.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -1,8 +1,8 @@ /** - * @file SampleGSComponents.cpp + * @file sample_ground_station_components.cpp * @brief An example of ground station related components list */ -#include "SampleGSComponents.h" +#include "sample_ground_station_components.hpp" #include diff --git a/src/simulation/ground_station/sample_ground_station/SampleGSComponents.h b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp similarity index 77% rename from src/simulation/ground_station/sample_ground_station/SampleGSComponents.h rename to src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index c4bfac686..b89314fdc 100644 --- a/src/simulation/ground_station/sample_ground_station/SampleGSComponents.h +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -1,9 +1,10 @@ /** - * @file SampleGSComponents.h + * @file sample_ground_station_components.hpp * @brief An example of ground station related components list */ -#pragma once +#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ +#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ #include #include @@ -47,3 +48,5 @@ class SampleGSComponents { GScalculator* gs_calculator_; //!< Ground station calculation algorithm const SimulationConfig* config_; //!< Simulation setting }; + +#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ From 0fe34b7cf9c734e62e1fb291c288806de3a9a960 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:36:14 +0100 Subject: [PATCH 0196/1086] Renamse Case directory --- CMakeLists.txt | 2 +- src/s2e.cpp | 2 +- src/simulation/CMakeLists.txt | 2 +- src/simulation/{Case => case}/SampleCase.cpp | 0 src/simulation/{Case => case}/SampleCase.h | 0 src/simulation/{Case => case}/SimulationCase.cpp | 0 src/simulation/{Case => case}/SimulationCase.h | 0 7 files changed, 3 insertions(+), 3 deletions(-) rename src/simulation/{Case => case}/SampleCase.cpp (100%) rename src/simulation/{Case => case}/SampleCase.h (100%) rename src/simulation/{Case => case}/SimulationCase.cpp (100%) rename src/simulation/{Case => case}/SimulationCase.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 636b62562..ef07b2535 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -87,7 +87,7 @@ add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES src/s2e.cpp - src/simulation/Case/SampleCase.cpp + src/simulation/case/SampleCase.cpp src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp diff --git a/src/s2e.cpp b/src/s2e.cpp index 3bfa934a5..14fda13e1 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -18,7 +18,7 @@ #include "Interface/LogOutput/Logger.h" // Add custom include files -#include "simulation/Case/SampleCase.h" +#include "simulation/case/SampleCase.h" // #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" // #include "Interface/HilsInOut/COSMOSWrapper.h" // #include "Interface/HilsInOut/HardwareMessage.h" diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 8f42aa27c..1842f5d1a 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -2,7 +2,7 @@ project(SIMULATION) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Case/SimulationCase.cpp + case/SimulationCase.cpp monte_carlo_simulation/monte_carlo_simulation_executor.cpp monte_carlo_simulation/simulation_object.cpp diff --git a/src/simulation/Case/SampleCase.cpp b/src/simulation/case/SampleCase.cpp similarity index 100% rename from src/simulation/Case/SampleCase.cpp rename to src/simulation/case/SampleCase.cpp diff --git a/src/simulation/Case/SampleCase.h b/src/simulation/case/SampleCase.h similarity index 100% rename from src/simulation/Case/SampleCase.h rename to src/simulation/case/SampleCase.h diff --git a/src/simulation/Case/SimulationCase.cpp b/src/simulation/case/SimulationCase.cpp similarity index 100% rename from src/simulation/Case/SimulationCase.cpp rename to src/simulation/case/SimulationCase.cpp diff --git a/src/simulation/Case/SimulationCase.h b/src/simulation/case/SimulationCase.h similarity index 100% rename from src/simulation/Case/SimulationCase.h rename to src/simulation/case/SimulationCase.h From 66acc89aa0cdb1035b023545a5c5cb201b09878d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:37:59 +0100 Subject: [PATCH 0197/1086] Renamse SimulationCase files --- src/simulation/CMakeLists.txt | 2 +- src/simulation/case/SampleCase.h | 2 +- .../case/{SimulationCase.cpp => simulation_case.cpp} | 4 ++-- src/simulation/case/{SimulationCase.h => simulation_case.hpp} | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) rename src/simulation/case/{SimulationCase.cpp => simulation_case.cpp} (97%) rename src/simulation/case/{SimulationCase.h => simulation_case.hpp} (98%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 1842f5d1a..0d90aa9ef 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -2,7 +2,7 @@ project(SIMULATION) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - case/SimulationCase.cpp + case/simulation_case.cpp monte_carlo_simulation/monte_carlo_simulation_executor.cpp monte_carlo_simulation/simulation_object.cpp diff --git a/src/simulation/case/SampleCase.h b/src/simulation/case/SampleCase.h index 74f4fe835..f3d5c6334 100644 --- a/src/simulation/case/SampleCase.h +++ b/src/simulation/case/SampleCase.h @@ -7,7 +7,7 @@ #include "../ground_station/sample_ground_station/sample_ground_station.hpp" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" -#include "./SimulationCase.h" +#include "./simulation_case.hpp" /** * @class SampleCase diff --git a/src/simulation/case/SimulationCase.cpp b/src/simulation/case/simulation_case.cpp similarity index 97% rename from src/simulation/case/SimulationCase.cpp rename to src/simulation/case/simulation_case.cpp index af4e5b6d2..df65ee9c4 100644 --- a/src/simulation/case/SimulationCase.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -1,9 +1,9 @@ /** - * @file SimulationCase.cpp + * @file simulation_case.cpp * @brief Base class to define simulation scenario */ -#include "SimulationCase.h" +#include "simulation_case.hpp" #include diff --git a/src/simulation/case/SimulationCase.h b/src/simulation/case/simulation_case.hpp similarity index 98% rename from src/simulation/case/SimulationCase.h rename to src/simulation/case/simulation_case.hpp index 3ea3d4cd0..cc7c3d086 100644 --- a/src/simulation/case/SimulationCase.h +++ b/src/simulation/case/simulation_case.hpp @@ -1,5 +1,5 @@ /** - * @file SimulationCase.h + * @file simulation_case.hpp * @brief Base class to define simulation scenario */ From 19552434548c79489c575fac2fcca7bccc66fcfa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:39:06 +0100 Subject: [PATCH 0198/1086] Fix include guard for simulation_case.hpp --- src/simulation/case/simulation_case.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index cc7c3d086..e01e3dd24 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -3,7 +3,8 @@ * @brief Base class to define simulation scenario */ -#pragma once +#ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ +#define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #include #include @@ -74,3 +75,5 @@ class SimulationCase : public ILoggable { SimulationConfig sim_config_; //!< Simulation setting GlobalEnvironment* glo_env_; //!< Global Environment }; + +#endif // S2E_SIMULATION_CASE_SIMULATION_CASE_H_ From f30c03cb11ea1dda4acc6547854e22dcbfc997d5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 11:41:59 +0100 Subject: [PATCH 0199/1086] Renamse SampleCase files --- CMakeLists.txt | 2 +- src/s2e.cpp | 2 +- src/simulation/case/{SampleCase.cpp => sample_case.cpp} | 4 ++-- src/simulation/case/{SampleCase.h => sample_case.hpp} | 7 +++++-- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/simulation/case/{SampleCase.cpp => sample_case.cpp} (98%) rename src/simulation/case/{SampleCase.h => sample_case.hpp} (87%) diff --git a/CMakeLists.txt b/CMakeLists.txt index ef07b2535..b45e6da95 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -87,7 +87,7 @@ add_subdirectory(src/Library/Geodesy) set(SOURCE_FILES src/s2e.cpp - src/simulation/case/SampleCase.cpp + src/simulation/case/sample_case.cpp src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp src/simulation/spacecraft/sample_spacecraft/sample_components.cpp src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp diff --git a/src/s2e.cpp b/src/s2e.cpp index 14fda13e1..289fbc60b 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -18,7 +18,7 @@ #include "Interface/LogOutput/Logger.h" // Add custom include files -#include "simulation/case/SampleCase.h" +#include "simulation/case/sample_case.hpp" // #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" // #include "Interface/HilsInOut/COSMOSWrapper.h" // #include "Interface/HilsInOut/HardwareMessage.h" diff --git a/src/simulation/case/SampleCase.cpp b/src/simulation/case/sample_case.cpp similarity index 98% rename from src/simulation/case/SampleCase.cpp rename to src/simulation/case/sample_case.cpp index 37392d7c4..687d4ba8d 100644 --- a/src/simulation/case/SampleCase.cpp +++ b/src/simulation/case/sample_case.cpp @@ -1,9 +1,9 @@ /** - * @file SampleCase.cpp + * @file sample_case.cpp * @brief Example of user defined simulation case */ -#include "SampleCase.h" +#include "sample_case.hpp" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" diff --git a/src/simulation/case/SampleCase.h b/src/simulation/case/sample_case.hpp similarity index 87% rename from src/simulation/case/SampleCase.h rename to src/simulation/case/sample_case.hpp index f3d5c6334..bae948cfe 100644 --- a/src/simulation/case/SampleCase.h +++ b/src/simulation/case/sample_case.hpp @@ -1,9 +1,10 @@ /** - * @file SampleCase.h + * @file sample_case.hpp * @brief Example of user defined simulation case */ -#pragma once +#ifndef S2E_SIMULATION_CASE_SAMPLE_CASE_H_ +#define S2E_SIMULATION_CASE_SAMPLE_CASE_H_ #include "../ground_station/sample_ground_station/sample_ground_station.hpp" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" @@ -54,3 +55,5 @@ class SampleCase : public SimulationCase { SampleSat* sample_sat_; //!< Instance of spacecraft SampleGS* sample_gs_; //!< Instance of ground station }; + +#endif // S2E_SIMULATION_CASE_SAMPLE_CASE_H_ From bdaf951001ecdcb2013b15d617d8945e2bf62b36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 12:06:11 +0100 Subject: [PATCH 0200/1086] Rename RelativeInformation directory --- src/{RelativeInformation => relative_information}/CMakeLists.txt | 0 .../RelativeInformation.cpp | 0 .../RelativeInformation.h | 0 3 files changed, 0 insertions(+), 0 deletions(-) rename src/{RelativeInformation => relative_information}/CMakeLists.txt (100%) rename src/{RelativeInformation => relative_information}/RelativeInformation.cpp (100%) rename src/{RelativeInformation => relative_information}/RelativeInformation.h (100%) diff --git a/src/RelativeInformation/CMakeLists.txt b/src/relative_information/CMakeLists.txt similarity index 100% rename from src/RelativeInformation/CMakeLists.txt rename to src/relative_information/CMakeLists.txt diff --git a/src/RelativeInformation/RelativeInformation.cpp b/src/relative_information/RelativeInformation.cpp similarity index 100% rename from src/RelativeInformation/RelativeInformation.cpp rename to src/relative_information/RelativeInformation.cpp diff --git a/src/RelativeInformation/RelativeInformation.h b/src/relative_information/RelativeInformation.h similarity index 100% rename from src/RelativeInformation/RelativeInformation.h rename to src/relative_information/RelativeInformation.h From ef8006f62c59bba70717ae6dfc1dc571546b0d04 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 12:09:16 +0100 Subject: [PATCH 0201/1086] Rename RelativeInformation directory --- CMakeLists.txt | 2 +- src/Dynamics/Dynamics.cpp | 2 +- src/Dynamics/Orbit/RelativeOrbit.h | 2 +- src/relative_information/CMakeLists.txt | 2 +- .../{RelativeInformation.cpp => relative_information.cpp} | 4 ++-- .../{RelativeInformation.h => relative_information.hpp} | 8 ++++++-- src/simulation/spacecraft/spacecraft.hpp | 3 ++- 7 files changed, 14 insertions(+), 9 deletions(-) rename src/relative_information/{RelativeInformation.cpp => relative_information.cpp} (99%) rename src/relative_information/{RelativeInformation.h => relative_information.hpp} (97%) diff --git a/CMakeLists.txt b/CMakeLists.txt index b45e6da95..f47e42503 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -69,7 +69,7 @@ add_subdirectory(src/Environment/Local) add_subdirectory(src/Dynamics) add_subdirectory(src/Disturbance) add_subdirectory(src/Component) -add_subdirectory(src/RelativeInformation) +add_subdirectory(src/relative_information) add_subdirectory(src/Interface/InitInput) add_subdirectory(src/Interface/LogOutput) add_subdirectory(src/Interface/SpacecraftInOut) diff --git a/src/Dynamics/Dynamics.cpp b/src/Dynamics/Dynamics.cpp index 81f7ce459..4bb0e7724 100644 --- a/src/Dynamics/Dynamics.cpp +++ b/src/Dynamics/Dynamics.cpp @@ -5,7 +5,7 @@ #include "Dynamics.h" -#include "../RelativeInformation/RelativeInformation.h" +#include "../relative_information/relative_information.hpp" using namespace std; diff --git a/src/Dynamics/Orbit/RelativeOrbit.h b/src/Dynamics/Orbit/RelativeOrbit.h index 0f1203fcf..bd073dd72 100644 --- a/src/Dynamics/Orbit/RelativeOrbit.h +++ b/src/Dynamics/Orbit/RelativeOrbit.h @@ -4,9 +4,9 @@ */ #pragma once #include -#include #include +#include #include #include "Orbit.h" diff --git a/src/relative_information/CMakeLists.txt b/src/relative_information/CMakeLists.txt index 14513f897..d09587d3c 100644 --- a/src/relative_information/CMakeLists.txt +++ b/src/relative_information/CMakeLists.txt @@ -2,7 +2,7 @@ project(RELATIVE_INFO) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - RelativeInformation.cpp + relative_information.cpp ) include(../../common.cmake) diff --git a/src/relative_information/RelativeInformation.cpp b/src/relative_information/relative_information.cpp similarity index 99% rename from src/relative_information/RelativeInformation.cpp rename to src/relative_information/relative_information.cpp index a7667c479..9cfa1c924 100644 --- a/src/relative_information/RelativeInformation.cpp +++ b/src/relative_information/relative_information.cpp @@ -1,9 +1,9 @@ /** - * @file RelativeInformation.cpp + * @file relative_information.cpp * @brief Base class to manage relative information between spacecraft */ -#include "RelativeInformation.h" +#include "relative_information.hpp" RelativeInformation::RelativeInformation() {} diff --git a/src/relative_information/RelativeInformation.h b/src/relative_information/relative_information.hpp similarity index 97% rename from src/relative_information/RelativeInformation.h rename to src/relative_information/relative_information.hpp index ea29691b0..68cf555bb 100644 --- a/src/relative_information/RelativeInformation.h +++ b/src/relative_information/relative_information.hpp @@ -1,9 +1,11 @@ /** - * @file RelativeInformation.h + * @file relative_information.hpp * @brief Base class to manage relative information between spacecraft */ -#pragma once +#ifndef S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ +#define S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ + #include #include "../Dynamics/Dynamics.h" @@ -168,3 +170,5 @@ class RelativeInformation : public ILoggable { */ void ResizeLists(); }; + +#endif // S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 2e8f81d22..f2b523135 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -10,7 +10,8 @@ #include #include #include -#include + +#include #include "installed_components.hpp" #include "structure/structure.hpp" From b3e1dcbb7ad5210522a3be4389c0020efad44f95 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 12:21:24 +0100 Subject: [PATCH 0202/1086] Renamce Disturbances directory --- CMakeLists.txt | 2 +- .../AccelerationDisturbance.h | 0 src/{Disturbance => disturbances}/AirDrag.cpp | 0 src/{Disturbance => disturbances}/AirDrag.h | 0 src/{Disturbance => disturbances}/CMakeLists.txt | 0 src/{Disturbance => disturbances}/Disturbance.h | 0 src/{Disturbance => disturbances}/Disturbances.cpp | 0 src/{Disturbance => disturbances}/Disturbances.h | 0 src/{Disturbance => disturbances}/GeoPotential.cpp | 0 src/{Disturbance => disturbances}/GeoPotential.h | 0 .../GravityGradient.cpp | 0 .../GravityGradient.hpp | 0 .../InitDisturbance.cpp | 0 .../InitDisturbance.hpp | 12 ++++++------ src/{Disturbance => disturbances}/MagDisturbance.cpp | 0 src/{Disturbance => disturbances}/MagDisturbance.h | 0 .../SimpleDisturbance.h | 0 src/{Disturbance => disturbances}/SolarRadiation.cpp | 0 src/{Disturbance => disturbances}/SolarRadiation.h | 0 src/{Disturbance => disturbances}/SurfaceForce.cpp | 0 src/{Disturbance => disturbances}/SurfaceForce.h | 0 .../ThirdBodyGravity.cpp | 0 src/{Disturbance => disturbances}/ThirdBodyGravity.h | 0 src/simulation/spacecraft/spacecraft.hpp | 2 +- 24 files changed, 8 insertions(+), 8 deletions(-) rename src/{Disturbance => disturbances}/AccelerationDisturbance.h (100%) rename src/{Disturbance => disturbances}/AirDrag.cpp (100%) rename src/{Disturbance => disturbances}/AirDrag.h (100%) rename src/{Disturbance => disturbances}/CMakeLists.txt (100%) rename src/{Disturbance => disturbances}/Disturbance.h (100%) rename src/{Disturbance => disturbances}/Disturbances.cpp (100%) rename src/{Disturbance => disturbances}/Disturbances.h (100%) rename src/{Disturbance => disturbances}/GeoPotential.cpp (100%) rename src/{Disturbance => disturbances}/GeoPotential.h (100%) rename src/{Disturbance => disturbances}/GravityGradient.cpp (100%) rename src/{Disturbance => disturbances}/GravityGradient.hpp (100%) rename src/{Disturbance => disturbances}/InitDisturbance.cpp (100%) rename src/{Disturbance => disturbances}/InitDisturbance.hpp (89%) rename src/{Disturbance => disturbances}/MagDisturbance.cpp (100%) rename src/{Disturbance => disturbances}/MagDisturbance.h (100%) rename src/{Disturbance => disturbances}/SimpleDisturbance.h (100%) rename src/{Disturbance => disturbances}/SolarRadiation.cpp (100%) rename src/{Disturbance => disturbances}/SolarRadiation.h (100%) rename src/{Disturbance => disturbances}/SurfaceForce.cpp (100%) rename src/{Disturbance => disturbances}/SurfaceForce.h (100%) rename src/{Disturbance => disturbances}/ThirdBodyGravity.cpp (100%) rename src/{Disturbance => disturbances}/ThirdBodyGravity.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index f47e42503..c28dc2e6b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -67,7 +67,7 @@ add_subdirectory(src/simulation) add_subdirectory(src/Environment/Global) add_subdirectory(src/Environment/Local) add_subdirectory(src/Dynamics) -add_subdirectory(src/Disturbance) +add_subdirectory(src/disturbances) add_subdirectory(src/Component) add_subdirectory(src/relative_information) add_subdirectory(src/Interface/InitInput) diff --git a/src/Disturbance/AccelerationDisturbance.h b/src/disturbances/AccelerationDisturbance.h similarity index 100% rename from src/Disturbance/AccelerationDisturbance.h rename to src/disturbances/AccelerationDisturbance.h diff --git a/src/Disturbance/AirDrag.cpp b/src/disturbances/AirDrag.cpp similarity index 100% rename from src/Disturbance/AirDrag.cpp rename to src/disturbances/AirDrag.cpp diff --git a/src/Disturbance/AirDrag.h b/src/disturbances/AirDrag.h similarity index 100% rename from src/Disturbance/AirDrag.h rename to src/disturbances/AirDrag.h diff --git a/src/Disturbance/CMakeLists.txt b/src/disturbances/CMakeLists.txt similarity index 100% rename from src/Disturbance/CMakeLists.txt rename to src/disturbances/CMakeLists.txt diff --git a/src/Disturbance/Disturbance.h b/src/disturbances/Disturbance.h similarity index 100% rename from src/Disturbance/Disturbance.h rename to src/disturbances/Disturbance.h diff --git a/src/Disturbance/Disturbances.cpp b/src/disturbances/Disturbances.cpp similarity index 100% rename from src/Disturbance/Disturbances.cpp rename to src/disturbances/Disturbances.cpp diff --git a/src/Disturbance/Disturbances.h b/src/disturbances/Disturbances.h similarity index 100% rename from src/Disturbance/Disturbances.h rename to src/disturbances/Disturbances.h diff --git a/src/Disturbance/GeoPotential.cpp b/src/disturbances/GeoPotential.cpp similarity index 100% rename from src/Disturbance/GeoPotential.cpp rename to src/disturbances/GeoPotential.cpp diff --git a/src/Disturbance/GeoPotential.h b/src/disturbances/GeoPotential.h similarity index 100% rename from src/Disturbance/GeoPotential.h rename to src/disturbances/GeoPotential.h diff --git a/src/Disturbance/GravityGradient.cpp b/src/disturbances/GravityGradient.cpp similarity index 100% rename from src/Disturbance/GravityGradient.cpp rename to src/disturbances/GravityGradient.cpp diff --git a/src/Disturbance/GravityGradient.hpp b/src/disturbances/GravityGradient.hpp similarity index 100% rename from src/Disturbance/GravityGradient.hpp rename to src/disturbances/GravityGradient.hpp diff --git a/src/Disturbance/InitDisturbance.cpp b/src/disturbances/InitDisturbance.cpp similarity index 100% rename from src/Disturbance/InitDisturbance.cpp rename to src/disturbances/InitDisturbance.cpp diff --git a/src/Disturbance/InitDisturbance.hpp b/src/disturbances/InitDisturbance.hpp similarity index 89% rename from src/Disturbance/InitDisturbance.hpp rename to src/disturbances/InitDisturbance.hpp index 909d3b99f..e9dbc0fc7 100644 --- a/src/Disturbance/InitDisturbance.hpp +++ b/src/disturbances/InitDisturbance.hpp @@ -5,13 +5,13 @@ #pragma once -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include +#include /** * @fn InitAirDrag diff --git a/src/Disturbance/MagDisturbance.cpp b/src/disturbances/MagDisturbance.cpp similarity index 100% rename from src/Disturbance/MagDisturbance.cpp rename to src/disturbances/MagDisturbance.cpp diff --git a/src/Disturbance/MagDisturbance.h b/src/disturbances/MagDisturbance.h similarity index 100% rename from src/Disturbance/MagDisturbance.h rename to src/disturbances/MagDisturbance.h diff --git a/src/Disturbance/SimpleDisturbance.h b/src/disturbances/SimpleDisturbance.h similarity index 100% rename from src/Disturbance/SimpleDisturbance.h rename to src/disturbances/SimpleDisturbance.h diff --git a/src/Disturbance/SolarRadiation.cpp b/src/disturbances/SolarRadiation.cpp similarity index 100% rename from src/Disturbance/SolarRadiation.cpp rename to src/disturbances/SolarRadiation.cpp diff --git a/src/Disturbance/SolarRadiation.h b/src/disturbances/SolarRadiation.h similarity index 100% rename from src/Disturbance/SolarRadiation.h rename to src/disturbances/SolarRadiation.h diff --git a/src/Disturbance/SurfaceForce.cpp b/src/disturbances/SurfaceForce.cpp similarity index 100% rename from src/Disturbance/SurfaceForce.cpp rename to src/disturbances/SurfaceForce.cpp diff --git a/src/Disturbance/SurfaceForce.h b/src/disturbances/SurfaceForce.h similarity index 100% rename from src/Disturbance/SurfaceForce.h rename to src/disturbances/SurfaceForce.h diff --git a/src/Disturbance/ThirdBodyGravity.cpp b/src/disturbances/ThirdBodyGravity.cpp similarity index 100% rename from src/Disturbance/ThirdBodyGravity.cpp rename to src/disturbances/ThirdBodyGravity.cpp diff --git a/src/Disturbance/ThirdBodyGravity.h b/src/disturbances/ThirdBodyGravity.h similarity index 100% rename from src/Disturbance/ThirdBodyGravity.h rename to src/disturbances/ThirdBodyGravity.h diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index f2b523135..5906dd7a5 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -6,10 +6,10 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ -#include #include #include #include +#include #include From cf60c25b1e7894af8c80af485275998dd2e2ffd2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 12:26:53 +0100 Subject: [PATCH 0203/1086] Rename AccelerationDisturbance --- src/disturbances/Disturbances.h | 2 +- src/disturbances/GeoPotential.h | 2 +- src/disturbances/ThirdBodyGravity.h | 2 +- ...lerationDisturbance.h => acceleration_disturbance.hpp} | 8 ++++++-- 4 files changed, 9 insertions(+), 5 deletions(-) rename src/disturbances/{AccelerationDisturbance.h => acceleration_disturbance.hpp} (84%) diff --git a/src/disturbances/Disturbances.h b/src/disturbances/Disturbances.h index 841d76294..d191b8c66 100644 --- a/src/disturbances/Disturbances.h +++ b/src/disturbances/Disturbances.h @@ -9,8 +9,8 @@ #include "../Environment/Global/SimTime.h" #include "../simulation/spacecraft/structure/structure.hpp" -#include "AccelerationDisturbance.h" #include "SimpleDisturbance.h" +#include "acceleration_disturbance.hpp" class Logger; diff --git a/src/disturbances/GeoPotential.h b/src/disturbances/GeoPotential.h index 3bccb05f5..99dfa7b15 100644 --- a/src/disturbances/GeoPotential.h +++ b/src/disturbances/GeoPotential.h @@ -11,7 +11,7 @@ #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" -#include "AccelerationDisturbance.h" +#include "acceleration_disturbance.hpp" using libra::Matrix; using libra::Vector; diff --git a/src/disturbances/ThirdBodyGravity.h b/src/disturbances/ThirdBodyGravity.h index 7bc527b29..f1b05cace 100644 --- a/src/disturbances/ThirdBodyGravity.h +++ b/src/disturbances/ThirdBodyGravity.h @@ -10,7 +10,7 @@ #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Vector.hpp" -#include "AccelerationDisturbance.h" +#include "acceleration_disturbance.hpp" /** * @class ThirdBodyGravity diff --git a/src/disturbances/AccelerationDisturbance.h b/src/disturbances/acceleration_disturbance.hpp similarity index 84% rename from src/disturbances/AccelerationDisturbance.h rename to src/disturbances/acceleration_disturbance.hpp index ce644f0d0..3a6c1a397 100644 --- a/src/disturbances/AccelerationDisturbance.h +++ b/src/disturbances/acceleration_disturbance.hpp @@ -1,9 +1,11 @@ /** - * @file AccelerationDisturbance.h + * @file acceleration_disturbance.hpp * @brief Abstract class for a disturbance which generate acceleration only (not force) */ -#pragma once +#ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ +#define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ + #include "../Dynamics/Dynamics.h" #include "../Environment/Local/LocalEnvironment.h" #include "Disturbance.h" @@ -39,3 +41,5 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { */ virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; }; + +#endif // S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ From 6c99b39ffe380bad42163a152e50272ecf3fc1a8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:18:17 +0100 Subject: [PATCH 0204/1086] Rename AirDrag --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/Disturbances.cpp | 2 +- src/disturbances/InitDisturbance.hpp | 2 +- src/disturbances/{AirDrag.cpp => air_drag.cpp} | 4 ++-- src/disturbances/{AirDrag.h => air_drag.hpp} | 9 +++++---- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/disturbances/{AirDrag.cpp => air_drag.cpp} (98%) rename src/disturbances/{AirDrag.h => air_drag.hpp} (94%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index 77947e419..d4d54fc6f 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -2,7 +2,7 @@ project(DISTURBANCE) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - AirDrag.cpp + air_drag.cpp Disturbances.cpp GeoPotential.cpp GravityGradient.cpp diff --git a/src/disturbances/Disturbances.cpp b/src/disturbances/Disturbances.cpp index 6e9a72b9b..448beee90 100644 --- a/src/disturbances/Disturbances.cpp +++ b/src/disturbances/Disturbances.cpp @@ -7,7 +7,7 @@ #include -#include "AirDrag.h" +#include "air_drag.hpp" #include "GeoPotential.h" #include "GravityGradient.hpp" #include "InitDisturbance.hpp" diff --git a/src/disturbances/InitDisturbance.hpp b/src/disturbances/InitDisturbance.hpp index e9dbc0fc7..f99fab88c 100644 --- a/src/disturbances/InitDisturbance.hpp +++ b/src/disturbances/InitDisturbance.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include #include #include diff --git a/src/disturbances/AirDrag.cpp b/src/disturbances/air_drag.cpp similarity index 98% rename from src/disturbances/AirDrag.cpp rename to src/disturbances/air_drag.cpp index 14f861089..8d1e9a89d 100644 --- a/src/disturbances/AirDrag.cpp +++ b/src/disturbances/air_drag.cpp @@ -1,9 +1,9 @@ /** - * @file AirDrag.cpp + * @file air_drag.cpp * @brief Class to calculate the air drag disturbance force and torque */ -#include "AirDrag.h" +#include "air_drag.hpp" #include #include diff --git a/src/disturbances/AirDrag.h b/src/disturbances/air_drag.hpp similarity index 94% rename from src/disturbances/AirDrag.h rename to src/disturbances/air_drag.hpp index c073c9fa2..3993af228 100644 --- a/src/disturbances/AirDrag.h +++ b/src/disturbances/air_drag.hpp @@ -1,10 +1,10 @@ /** - * @file AirDrag.h + * @file air_drag.hpp * @brief Class to calculate the air drag disturbance force and torque */ -#ifndef __AirDrag_H__ -#define __AirDrag_H__ +#ifndef S2E_DISTURBANCES_AIR_DRAG_H_ +#define S2E_DISTURBANCES_AIR_DRAG_H_ #include #include @@ -86,4 +86,5 @@ class AirDrag : public SurfaceForce { */ double funcChi(double s); }; -#endif + +#endif // S2E_DISTURBANCES_AIR_DRAG_H_ From 0469e7e2933d6de80bbdd448429762354de72654 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:21:01 +0100 Subject: [PATCH 0205/1086] Rename Disturbance.h --- src/disturbances/SimpleDisturbance.h | 2 +- src/disturbances/acceleration_disturbance.hpp | 2 +- src/disturbances/{Disturbance.h => disturbance.hpp} | 7 +++++-- 3 files changed, 7 insertions(+), 4 deletions(-) rename src/disturbances/{Disturbance.h => disturbance.hpp} (90%) diff --git a/src/disturbances/SimpleDisturbance.h b/src/disturbances/SimpleDisturbance.h index e97855939..7204a8b3b 100644 --- a/src/disturbances/SimpleDisturbance.h +++ b/src/disturbances/SimpleDisturbance.h @@ -8,7 +8,7 @@ #pragma once #include "../Dynamics/Dynamics.h" #include "../Environment/Local/LocalEnvironment.h" -#include "Disturbance.h" +#include "disturbance.hpp" /** * @class SimpleDisturbance diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index 3a6c1a397..2d1ec1df6 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -8,7 +8,7 @@ #include "../Dynamics/Dynamics.h" #include "../Environment/Local/LocalEnvironment.h" -#include "Disturbance.h" +#include "disturbance.hpp" /** * @class AccelerationDisturbance diff --git a/src/disturbances/Disturbance.h b/src/disturbances/disturbance.hpp similarity index 90% rename from src/disturbances/Disturbance.h rename to src/disturbances/disturbance.hpp index 935c639a3..f7d009c77 100644 --- a/src/disturbances/Disturbance.h +++ b/src/disturbances/disturbance.hpp @@ -1,9 +1,10 @@ /** - * @file Disturbance.h + * @file disturbance.hpp * @brief Base class for a disturbance */ -#pragma once +#ifndef S2E_DISTURBANCES_DISTURBANCE_H_ +#define S2E_DISTURBANCES_DISTURBANCE_H_ #include "../Library/math/Vector.hpp" using libra::Vector; @@ -54,3 +55,5 @@ class Disturbance { Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] }; + +#endif // S2E_DISTURBANCES_DISTURBANCE_H_ From 347d291bde9d1f416e7e5767b891421bcd1f9722 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:22:16 +0100 Subject: [PATCH 0206/1086] Rename Disturbances --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/{Disturbances.cpp => disturbances.cpp} | 6 +++--- src/disturbances/{Disturbances.h => disturbances.hpp} | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) rename src/disturbances/{Disturbances.cpp => disturbances.cpp} (98%) rename src/disturbances/{Disturbances.h => disturbances.hpp} (98%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index d4d54fc6f..f75b842a3 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC air_drag.cpp - Disturbances.cpp + disturbances.cpp GeoPotential.cpp GravityGradient.cpp MagDisturbance.cpp diff --git a/src/disturbances/Disturbances.cpp b/src/disturbances/disturbances.cpp similarity index 98% rename from src/disturbances/Disturbances.cpp rename to src/disturbances/disturbances.cpp index 448beee90..bf8b96268 100644 --- a/src/disturbances/Disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -1,19 +1,19 @@ /** - * @file Disturbances.cpp + * @file disturbances.cpp * @brief Class to manage all disturbances */ -#include "Disturbances.h" +#include "disturbances.hpp" #include -#include "air_drag.hpp" #include "GeoPotential.h" #include "GravityGradient.hpp" #include "InitDisturbance.hpp" #include "MagDisturbance.h" #include "SolarRadiation.h" #include "ThirdBodyGravity.h" +#include "air_drag.hpp" Disturbances::Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { InitializeInstances(sim_config, sat_id, structure, glo_env); diff --git a/src/disturbances/Disturbances.h b/src/disturbances/disturbances.hpp similarity index 98% rename from src/disturbances/Disturbances.h rename to src/disturbances/disturbances.hpp index d191b8c66..95395eb45 100644 --- a/src/disturbances/Disturbances.h +++ b/src/disturbances/disturbances.hpp @@ -1,5 +1,5 @@ /** - * @file Disturbances.h + * @file disturbances.hpp * @brief Class to manage all disturbances */ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 5906dd7a5..07e6449fe 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -9,8 +9,8 @@ #include #include #include -#include +#include #include #include "installed_components.hpp" From f027b091679838865596fdc11981dee61584e3af Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:22:55 +0100 Subject: [PATCH 0207/1086] Rename Disturbances --- src/disturbances/disturbances.hpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 95395eb45..5a0e1e584 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -3,7 +3,8 @@ * @brief Class to manage all disturbances */ -#pragma once +#ifndef S2E_DISTURBANCES_DISTURBANCES_H_ +#define S2E_DISTURBANCES_DISTURBANCES_H_ #include @@ -83,3 +84,5 @@ class Disturbances { */ void InitializeAcceleration(); }; + +#endif // S2E_DISTURBANCES_DISTURBANCES_H_ From 98574480bafc63e4b7ee45db00bbcbc0aa5a207f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:26:42 +0100 Subject: [PATCH 0208/1086] Rename Geopotential --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/InitDisturbance.hpp | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/{GeoPotential.cpp => geopotential.cpp} | 4 ++-- src/disturbances/{GeoPotential.h => geopotential.hpp} | 9 +++++---- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/disturbances/{GeoPotential.cpp => geopotential.cpp} (99%) rename src/disturbances/{GeoPotential.h => geopotential.hpp} (94%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index f75b842a3..afee308d0 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC air_drag.cpp disturbances.cpp - GeoPotential.cpp + geopotential.cpp GravityGradient.cpp MagDisturbance.cpp SolarRadiation.cpp diff --git a/src/disturbances/InitDisturbance.hpp b/src/disturbances/InitDisturbance.hpp index f99fab88c..1167c4874 100644 --- a/src/disturbances/InitDisturbance.hpp +++ b/src/disturbances/InitDisturbance.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include #include #include diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index bf8b96268..cef71f732 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -7,7 +7,7 @@ #include -#include "GeoPotential.h" +#include "geopotential.hpp" #include "GravityGradient.hpp" #include "InitDisturbance.hpp" #include "MagDisturbance.h" diff --git a/src/disturbances/GeoPotential.cpp b/src/disturbances/geopotential.cpp similarity index 99% rename from src/disturbances/GeoPotential.cpp rename to src/disturbances/geopotential.cpp index 9b055d7cc..e6161704f 100644 --- a/src/disturbances/GeoPotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -1,9 +1,9 @@ /** - * @file GeoPotential.cpp + * @file geopotential.cpp * @brief Class to calculate the high-order earth gravity acceleration */ -#include "GeoPotential.h" +#include "geopotential.hpp" #include #include diff --git a/src/disturbances/GeoPotential.h b/src/disturbances/geopotential.hpp similarity index 94% rename from src/disturbances/GeoPotential.h rename to src/disturbances/geopotential.hpp index 99dfa7b15..44d97f97a 100644 --- a/src/disturbances/GeoPotential.h +++ b/src/disturbances/geopotential.hpp @@ -1,10 +1,11 @@ /** - * @file GeoPotential.h + * @file geopotential.hpp * @brief Class to calculate the high-order earth gravity acceleration */ -#ifndef __GEOPOTENTIAL_H__ -#define __GEOPOTENTIAL_H__ +#ifndef S2E_DISTURBANCES_GEOPOTENTIAL_H_ +#define S2E_DISTURBANCES_GEOPOTENTIAL_H_ + #include #include "../Interface/LogOutput/ILoggable.h" @@ -86,4 +87,4 @@ class GeoPotential : public AccelerationDisturbance { double time_ = 0.0; //!< Calculation time [ms] }; -#endif //__GEOPOTENTIAL_H__ +#endif // S2E_DISTURBANCES_GEOPOTENTIAL_H_ From 6621cf8e922369cb07496cd33ba48f4d57b39a5b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:31:15 +0100 Subject: [PATCH 0209/1086] Rename GravityGradient --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/InitDisturbance.hpp | 2 +- src/disturbances/disturbances.cpp | 2 +- .../{GravityGradient.cpp => gravity_gradient.cpp} | 4 ++-- .../{GravityGradient.hpp => gravity_gradient.hpp} | 9 +++++---- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/disturbances/{GravityGradient.cpp => gravity_gradient.cpp} (95%) rename src/disturbances/{GravityGradient.hpp => gravity_gradient.hpp} (90%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index afee308d0..4f2814aa9 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC air_drag.cpp disturbances.cpp geopotential.cpp - GravityGradient.cpp + gravity_gradient.cpp MagDisturbance.cpp SolarRadiation.cpp SurfaceForce.cpp diff --git a/src/disturbances/InitDisturbance.hpp b/src/disturbances/InitDisturbance.hpp index 1167c4874..8f3e51301 100644 --- a/src/disturbances/InitDisturbance.hpp +++ b/src/disturbances/InitDisturbance.hpp @@ -11,7 +11,7 @@ #include #include -#include +#include /** * @fn InitAirDrag diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index cef71f732..c6c17b815 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -8,7 +8,7 @@ #include #include "geopotential.hpp" -#include "GravityGradient.hpp" +#include "gravity_gradient.hpp" #include "InitDisturbance.hpp" #include "MagDisturbance.h" #include "SolarRadiation.h" diff --git a/src/disturbances/GravityGradient.cpp b/src/disturbances/gravity_gradient.cpp similarity index 95% rename from src/disturbances/GravityGradient.cpp rename to src/disturbances/gravity_gradient.cpp index 43dd83e9a..98ff42fa8 100644 --- a/src/disturbances/GravityGradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -1,9 +1,9 @@ /** - * @file GravityGradient.cpp + * @file gravity_gradient.cpp * @brief Class to calculate the gravity gradient torque */ -#include "GravityGradient.hpp" +#include "gravity_gradient.hpp" #include #include diff --git a/src/disturbances/GravityGradient.hpp b/src/disturbances/gravity_gradient.hpp similarity index 90% rename from src/disturbances/GravityGradient.hpp rename to src/disturbances/gravity_gradient.hpp index eaeea5c6d..d91832b81 100644 --- a/src/disturbances/GravityGradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -1,10 +1,11 @@ /** - * @file GravityGradient.hpp + * @file gravity_gradient.hpp * @brief Class to calculate the gravity gradient torque */ -#ifndef __GravityGradient_H__ -#define __GravityGradient_H__ +#ifndef S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ +#define S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ + #include #include "../Interface/LogOutput/ILoggable.h" @@ -65,4 +66,4 @@ class GravityGradient : public SimpleDisturbance { double mu_m3_s2_; //!< Gravitational constant [m3/s2] }; -#endif //__GravityGradient_H__ +#endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ From 82dd2fc0c8f7565d2da6c4dbd5c105d8fb4dfcbe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:33:20 +0100 Subject: [PATCH 0210/1086] Rename InitDisturbance --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/disturbances.cpp | 2 +- ...nitDisturbance.cpp => initialize_disturbances.cpp} | 4 ++-- ...nitDisturbance.hpp => initialize_disturbances.hpp} | 11 +++++++---- 4 files changed, 11 insertions(+), 8 deletions(-) rename src/disturbances/{InitDisturbance.cpp => initialize_disturbances.cpp} (98%) rename src/disturbances/{InitDisturbance.hpp => initialize_disturbances.hpp} (92%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index 4f2814aa9..934580ff6 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -10,6 +10,6 @@ add_library(${PROJECT_NAME} STATIC SolarRadiation.cpp SurfaceForce.cpp ThirdBodyGravity.cpp - InitDisturbance.cpp + initialize_disturbances.cpp ) include(../../common.cmake) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index c6c17b815..4f9b0bde9 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -9,7 +9,7 @@ #include "geopotential.hpp" #include "gravity_gradient.hpp" -#include "InitDisturbance.hpp" +#include "initialize_disturbances.hpp" #include "MagDisturbance.h" #include "SolarRadiation.h" #include "ThirdBodyGravity.h" diff --git a/src/disturbances/InitDisturbance.cpp b/src/disturbances/initialize_disturbances.cpp similarity index 98% rename from src/disturbances/InitDisturbance.cpp rename to src/disturbances/initialize_disturbances.cpp index ead9e58cf..193564baa 100644 --- a/src/disturbances/InitDisturbance.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -1,9 +1,9 @@ /** - * @file InitDisturbance.cpp + * @file initialize_disturbances.cpp * @brief Define initialize functions for disturbances */ -#include "InitDisturbance.hpp" +#include "initialize_disturbances.hpp" #include diff --git a/src/disturbances/InitDisturbance.hpp b/src/disturbances/initialize_disturbances.hpp similarity index 92% rename from src/disturbances/InitDisturbance.hpp rename to src/disturbances/initialize_disturbances.hpp index 8f3e51301..209f923c2 100644 --- a/src/disturbances/InitDisturbance.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -1,16 +1,17 @@ /** - * @file InitDisturbance.hpp + * @file initialize_disturbances.hpp * @brief Define initialize functions for disturbances */ -#pragma once +#ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ +#define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ -#include -#include #include #include #include +#include +#include #include /** @@ -64,3 +65,5 @@ GeoPotential InitGeoPotential(std::string ini_path); * @param [in] ini_path_celes: Initialize file path for the celestial information */ ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes); + +#endif // S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ From 3b0348161d8e008e49dcf9875e1b3337a723437d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:36:52 +0100 Subject: [PATCH 0211/1086] Rename MagDisturbance --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/disturbances.cpp | 8 ++++---- src/disturbances/initialize_disturbances.hpp | 2 +- .../{MagDisturbance.cpp => magnetic_disturbance.cpp} | 4 ++-- .../{MagDisturbance.h => magnetic_disturbance.hpp} | 8 ++++---- 5 files changed, 12 insertions(+), 12 deletions(-) rename src/disturbances/{MagDisturbance.cpp => magnetic_disturbance.cpp} (96%) rename src/disturbances/{MagDisturbance.h => magnetic_disturbance.hpp} (89%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index 934580ff6..f90d2a2fc 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC disturbances.cpp geopotential.cpp gravity_gradient.cpp - MagDisturbance.cpp + magnetic_disturbance.cpp SolarRadiation.cpp SurfaceForce.cpp ThirdBodyGravity.cpp diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 4f9b0bde9..db80b598f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -7,13 +7,13 @@ #include -#include "geopotential.hpp" -#include "gravity_gradient.hpp" -#include "initialize_disturbances.hpp" -#include "MagDisturbance.h" #include "SolarRadiation.h" #include "ThirdBodyGravity.h" #include "air_drag.hpp" +#include "geopotential.hpp" +#include "gravity_gradient.hpp" +#include "initialize_disturbances.hpp" +#include "magnetic_disturbance.hpp" Disturbances::Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { InitializeInstances(sim_config, sat_id, structure, glo_env); diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index 209f923c2..e32759401 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -6,13 +6,13 @@ #ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ #define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ -#include #include #include #include #include #include +#include /** * @fn InitAirDrag diff --git a/src/disturbances/MagDisturbance.cpp b/src/disturbances/magnetic_disturbance.cpp similarity index 96% rename from src/disturbances/MagDisturbance.cpp rename to src/disturbances/magnetic_disturbance.cpp index 2c7fb56c4..267dbf34d 100644 --- a/src/disturbances/MagDisturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -1,9 +1,9 @@ /** - * @file MagDisturbance.cpp + * @file magnetic_disturbances.cpp * @brief Class to calculate the magnetic disturbance torque */ -#include "MagDisturbance.h" +#include "magnetic_disturbance.hpp" #include "../Library/math/NormalRand.hpp" using libra::NormalRand; diff --git a/src/disturbances/MagDisturbance.h b/src/disturbances/magnetic_disturbance.hpp similarity index 89% rename from src/disturbances/MagDisturbance.h rename to src/disturbances/magnetic_disturbance.hpp index 9049e5a53..9eed46f0a 100644 --- a/src/disturbances/MagDisturbance.h +++ b/src/disturbances/magnetic_disturbance.hpp @@ -1,10 +1,10 @@ /** - * @file MagDisturbance.h + * @file magnetic_disturbance.hpp * @brief Class to calculate the magnetic disturbance torque */ -#ifndef __MagDisturbance_H__ -#define __MagDisturbance_H__ +#ifndef S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ +#define S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ #include @@ -68,4 +68,4 @@ class MagDisturbance : public SimpleDisturbance { const RMMParams& rmm_params_; //!< RMM parameters }; -#endif //__MagDisturbance_H__ +#endif // S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ From 5c65bb4fae955d43a68cc74301eee221086264ed Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:39:42 +0100 Subject: [PATCH 0212/1086] Rename SimpleDisturbance --- src/disturbances/SurfaceForce.h | 2 +- src/disturbances/disturbances.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- .../{SimpleDisturbance.h => simple_disturbance.hpp} | 8 ++++++-- 5 files changed, 10 insertions(+), 6 deletions(-) rename src/disturbances/{SimpleDisturbance.h => simple_disturbance.hpp} (86%) diff --git a/src/disturbances/SurfaceForce.h b/src/disturbances/SurfaceForce.h index 380381a61..cbf86897a 100644 --- a/src/disturbances/SurfaceForce.h +++ b/src/disturbances/SurfaceForce.h @@ -11,7 +11,7 @@ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" -#include "SimpleDisturbance.h" +#include "simple_disturbance.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 5a0e1e584..202ef8c45 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -10,7 +10,7 @@ #include "../Environment/Global/SimTime.h" #include "../simulation/spacecraft/structure/structure.hpp" -#include "SimpleDisturbance.h" +#include "simple_disturbance.hpp" #include "acceleration_disturbance.hpp" class Logger; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index d91832b81..59f76fe80 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -12,7 +12,7 @@ #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" -#include "SimpleDisturbance.h" +#include "simple_disturbance.hpp" using libra::Matrix; using libra::Vector; diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 9eed46f0a..a5a99819a 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -13,7 +13,7 @@ using libra::Vector; #include "../Interface/LogOutput/ILoggable.h" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" -#include "SimpleDisturbance.h" +#include "simple_disturbance.hpp" /** * @class MagDisturbance diff --git a/src/disturbances/SimpleDisturbance.h b/src/disturbances/simple_disturbance.hpp similarity index 86% rename from src/disturbances/SimpleDisturbance.h rename to src/disturbances/simple_disturbance.hpp index 7204a8b3b..592092211 100644 --- a/src/disturbances/SimpleDisturbance.h +++ b/src/disturbances/simple_disturbance.hpp @@ -1,11 +1,13 @@ /** - * @file SimpleDisturbance.h + * @file simple_disturbance.hpp * @brief Abstract class for a disturbance * @note It is better to use this abstract class for all disturbances, but it is difficult. (e.g. Gravity between spacecraft.) * In the difficult case, users need to use the Disturbance class directory. */ -#pragma once +#ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ +#define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ + #include "../Dynamics/Dynamics.h" #include "../Environment/Local/LocalEnvironment.h" #include "disturbance.hpp" @@ -41,3 +43,5 @@ class SimpleDisturbance : public Disturbance, public ILoggable { */ virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; }; + +#endif // S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ From a92dd44eac28ac16bf7e74358c80165ccb0955ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:43:14 +0100 Subject: [PATCH 0213/1086] Rename SolarRadiation --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.hpp | 2 +- ...tion.cpp => solar_radiation_pressure_disturbance.cpp} | 4 ++-- ...iation.h => solar_radiation_pressure_disturbance.hpp} | 9 +++++---- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/disturbances/{SolarRadiation.cpp => solar_radiation_pressure_disturbance.cpp} (93%) rename src/disturbances/{SolarRadiation.h => solar_radiation_pressure_disturbance.hpp} (84%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index f90d2a2fc..eeabbc5c4 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -7,7 +7,7 @@ add_library(${PROJECT_NAME} STATIC geopotential.cpp gravity_gradient.cpp magnetic_disturbance.cpp - SolarRadiation.cpp + solar_radiation_pressure_disturbance.cpp SurfaceForce.cpp ThirdBodyGravity.cpp initialize_disturbances.cpp diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index db80b598f..8add59d49 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -7,7 +7,7 @@ #include -#include "SolarRadiation.h" +#include "solar_radiation_pressure_disturbance.hpp" #include "ThirdBodyGravity.h" #include "air_drag.hpp" #include "geopotential.hpp" diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index e32759401..c9fd4d231 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ #define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ -#include +#include #include #include diff --git a/src/disturbances/SolarRadiation.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp similarity index 93% rename from src/disturbances/SolarRadiation.cpp rename to src/disturbances/solar_radiation_pressure_disturbance.cpp index 7432ce373..26fe3ff29 100644 --- a/src/disturbances/SolarRadiation.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -1,9 +1,9 @@ /** - * @file SolarRadiation.cpp + * @file solar_radiation_pressure_disturbance.cpp * @brief Class to calculate the solar radiation pressure disturbance force and torque */ -#include "SolarRadiation.h" +#include "solar_radiation_pressure_disturbance.hpp" #include diff --git a/src/disturbances/SolarRadiation.h b/src/disturbances/solar_radiation_pressure_disturbance.hpp similarity index 84% rename from src/disturbances/SolarRadiation.h rename to src/disturbances/solar_radiation_pressure_disturbance.hpp index a84caea19..cf16a90b0 100644 --- a/src/disturbances/SolarRadiation.h +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -1,10 +1,11 @@ /** - * @file SolarRadiation.h + * @file solar_radiation_pressure_disturbance.hpp * @brief Class to calculate the solar radiation pressure disturbance force and torque */ -#ifndef __SolarRadiation_h__ -#define __SolarRadiation_h__ +#ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ +#define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ + #include #include @@ -53,4 +54,4 @@ class SolarRadiation : public SurfaceForce { virtual void CalcCoef(Vector<3>& input_b, double item); }; -#endif /* SolarRadiation_h */ +#endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ From f1184eecc2867c1db5c748fdd0daa217ef8884c1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:45:01 +0100 Subject: [PATCH 0214/1086] Rename SurfaceForce --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/air_drag.hpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/{SurfaceForce.cpp => surface_force.cpp} | 4 ++-- src/disturbances/{SurfaceForce.h => surface_force.hpp} | 9 +++++---- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/disturbances/{SurfaceForce.cpp => surface_force.cpp} (96%) rename src/disturbances/{SurfaceForce.h => surface_force.hpp} (93%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index eeabbc5c4..b3b1429fc 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -8,7 +8,7 @@ add_library(${PROJECT_NAME} STATIC gravity_gradient.cpp magnetic_disturbance.cpp solar_radiation_pressure_disturbance.cpp - SurfaceForce.cpp + surface_force.cpp ThirdBodyGravity.cpp initialize_disturbances.cpp ) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 3993af228..4dbcc2a06 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -13,7 +13,7 @@ #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" -#include "SurfaceForce.h" +#include "surface_force.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index cf16a90b0..562b03657 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -11,7 +11,7 @@ #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Vector.hpp" -#include "SurfaceForce.h" +#include "surface_force.hpp" using libra::Vector; /** diff --git a/src/disturbances/SurfaceForce.cpp b/src/disturbances/surface_force.cpp similarity index 96% rename from src/disturbances/SurfaceForce.cpp rename to src/disturbances/surface_force.cpp index 7eebab51b..2268f1fd5 100644 --- a/src/disturbances/SurfaceForce.cpp +++ b/src/disturbances/surface_force.cpp @@ -1,9 +1,9 @@ /** - * @file SurfaceForce.cpp + * @file surface_force.cpp * @brief Base class for disturbances acting on a spacecraft surface (e.g., SRP, Air drag, etc) */ -#include "SurfaceForce.h" +#include "surface_force.hpp" #include "../Library/math/Vector.hpp" using libra::Quaternion; diff --git a/src/disturbances/SurfaceForce.h b/src/disturbances/surface_force.hpp similarity index 93% rename from src/disturbances/SurfaceForce.h rename to src/disturbances/surface_force.hpp index cbf86897a..2c13dae45 100644 --- a/src/disturbances/SurfaceForce.h +++ b/src/disturbances/surface_force.hpp @@ -1,12 +1,12 @@ /** - * @file SurfaceForce.h + * @file surface_force.hpp * @brief Base class for disturbances acting on a spacecraft surface (e.g., SRP, Air drag, etc) */ #pragma once -#ifndef __SurfaceForce_H__ -#define __SurfaceForce_H__ +#ifndef S2E_DISTURBANCES_SURFACE_FORCE_H_ +#define S2E_DISTURBANCES_SURFACE_FORCE_H_ #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" @@ -69,4 +69,5 @@ class SurfaceForce : public SimpleDisturbance { */ virtual void CalcCoef(Vector<3>& input_b, double item) = 0; }; -#endif + +#endif // S2E_DISTURBANCES_SURFACE_FORCE_H_ From 9b5f40bc4012e042be1d2d8c592ad97739b538e0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:46:51 +0100 Subject: [PATCH 0215/1086] Rename ThirdBody --- src/disturbances/CMakeLists.txt | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.hpp | 2 +- .../{ThirdBodyGravity.cpp => third_body_gravity.cpp} | 4 ++-- .../{ThirdBodyGravity.h => third_body_gravity.hpp} | 8 ++++++-- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/disturbances/{ThirdBodyGravity.cpp => third_body_gravity.cpp} (96%) rename src/disturbances/{ThirdBodyGravity.h => third_body_gravity.hpp} (91%) diff --git a/src/disturbances/CMakeLists.txt b/src/disturbances/CMakeLists.txt index b3b1429fc..1c3e73150 100644 --- a/src/disturbances/CMakeLists.txt +++ b/src/disturbances/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(${PROJECT_NAME} STATIC magnetic_disturbance.cpp solar_radiation_pressure_disturbance.cpp surface_force.cpp - ThirdBodyGravity.cpp + third_body_gravity.cpp initialize_disturbances.cpp ) include(../../common.cmake) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 8add59d49..f2e82be35 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -8,7 +8,7 @@ #include #include "solar_radiation_pressure_disturbance.hpp" -#include "ThirdBodyGravity.h" +#include "third_body_gravity.hpp" #include "air_drag.hpp" #include "geopotential.hpp" #include "gravity_gradient.hpp" diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index c9fd4d231..c05f3e857 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -7,7 +7,7 @@ #define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ #include -#include +#include #include #include diff --git a/src/disturbances/ThirdBodyGravity.cpp b/src/disturbances/third_body_gravity.cpp similarity index 96% rename from src/disturbances/ThirdBodyGravity.cpp rename to src/disturbances/third_body_gravity.cpp index 9690ead46..655c1cff2 100644 --- a/src/disturbances/ThirdBodyGravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -1,9 +1,9 @@ /** - * @file ThirdBodyGravity.cpp + * @file third_body_gravity.cpp * @brief Class to calculate third body gravity disturbance */ -#include "ThirdBodyGravity.h" +#include "third_body_gravity.hpp" ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list) : third_body_list_(third_body_list) { acceleration_i_ *= 0; } diff --git a/src/disturbances/ThirdBodyGravity.h b/src/disturbances/third_body_gravity.hpp similarity index 91% rename from src/disturbances/ThirdBodyGravity.h rename to src/disturbances/third_body_gravity.hpp index f1b05cace..fb4a3afee 100644 --- a/src/disturbances/ThirdBodyGravity.h +++ b/src/disturbances/third_body_gravity.hpp @@ -1,9 +1,11 @@ /** - * @file ThirdBodyGravity.h + * @file third_body_gravity.hpp * @brief Class to calculate third body gravity disturbance */ -#pragma once +#ifndef S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ +#define S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ + #include #include #include @@ -61,3 +63,5 @@ class ThirdBodyGravity : public AccelerationDisturbance { std::set third_body_list_; //!< List of celestial bodies to calculate the third body disturbances libra::Vector<3> thirdbody_acc_i_{0}; //!< Calculated third body disturbance acceleration in the inertial frame [m/s2] }; + +#endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ From cfa18e9d44e6dd86a98ab001d864e140ab428b84 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 13:55:57 +0100 Subject: [PATCH 0216/1086] Renamce Environment directory --- CMakeLists.txt | 4 ++-- src/Component/AOCS/GNSSReceiver.cpp | 2 +- src/Component/AOCS/GNSSReceiver.h | 4 ++-- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/STT.cpp | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/AOCS/SunSensor.h | 4 ++-- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/CommGS/GScalculator.cpp | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 4 ++-- src/Component/Power/PCU_InitialStudy.cpp | 2 +- src/Component/Power/SAP.cpp | 2 +- src/Component/Power/SAP.h | 4 ++-- src/Dynamics/Attitude/ControlledAttitude.h | 2 +- src/Dynamics/Dynamics.h | 4 ++-- src/Dynamics/Orbit/Orbit.h | 4 ++-- src/Dynamics/Orbit/Rk4OrbitPropagation.h | 2 +- src/Dynamics/Orbit/Sgp4OrbitPropagation.h | 2 +- src/Dynamics/Thermal/InitTemperature.cpp | 2 +- src/Dynamics/Thermal/Node.cpp | 2 +- src/Library/Geodesy/GeodeticPosition.cpp | 2 +- src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp | 2 +- src/disturbances/acceleration_disturbance.hpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/disturbances.hpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/simple_disturbance.hpp | 2 +- .../Global => environment/global}/CMakeLists.txt | 0 .../Global => environment/global}/CelestialInformation.cpp | 0 .../Global => environment/global}/CelestialInformation.h | 0 .../Global => environment/global}/CelestialRotation.cpp | 0 .../Global => environment/global}/CelestialRotation.h | 0 .../Global => environment/global}/ClockGenerator.cpp | 0 .../Global => environment/global}/ClockGenerator.h | 0 .../Global => environment/global}/GlobalEnvironment.cpp | 0 .../Global => environment/global}/GlobalEnvironment.h | 0 .../Global => environment/global}/GnssSatellites.cpp | 2 +- .../Global => environment/global}/GnssSatellites.h | 0 .../Global => environment/global}/HipparcosCatalogue.cpp | 0 .../Global => environment/global}/HipparcosCatalogue.h | 0 .../Global => environment/global}/InitGlobalEnvironment.cpp | 2 +- .../Global => environment/global}/InitGlobalEnvironment.hpp | 6 +++--- .../Global => environment/global}/InitGnssSatellites.cpp | 0 .../Global => environment/global}/InitGnssSatellites.hpp | 2 +- .../Global => environment/global}/PhysicalConstants.hpp | 0 src/{Environment/Global => environment/global}/SimTime.cpp | 0 src/{Environment/Global => environment/global}/SimTime.h | 0 src/{Environment/Local => environment/local}/Atmosphere.cpp | 0 src/{Environment/Local => environment/local}/Atmosphere.h | 0 src/{Environment/Local => environment/local}/CMakeLists.txt | 0 .../Local => environment/local}/InitLocalEnvironment.cpp | 0 .../Local => environment/local}/InitLocalEnvironment.hpp | 6 +++--- .../local}/LocalCelestialInformation.cpp | 0 .../Local => environment/local}/LocalCelestialInformation.h | 2 +- .../Local => environment/local}/LocalEnvironment.cpp | 0 .../Local => environment/local}/LocalEnvironment.h | 2 +- .../Local => environment/local}/MagEnvironment.cpp | 0 .../Local => environment/local}/MagEnvironment.h | 0 .../Local => environment/local}/SRPEnvironment.cpp | 2 +- .../Local => environment/local}/SRPEnvironment.h | 2 +- src/simulation/case/simulation_case.hpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- src/simulation/ground_station/ground_station.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 4 ++-- 70 files changed, 58 insertions(+), 58 deletions(-) rename src/{Environment/Global => environment/global}/CMakeLists.txt (100%) rename src/{Environment/Global => environment/global}/CelestialInformation.cpp (100%) rename src/{Environment/Global => environment/global}/CelestialInformation.h (100%) rename src/{Environment/Global => environment/global}/CelestialRotation.cpp (100%) rename src/{Environment/Global => environment/global}/CelestialRotation.h (100%) rename src/{Environment/Global => environment/global}/ClockGenerator.cpp (100%) rename src/{Environment/Global => environment/global}/ClockGenerator.h (100%) rename src/{Environment/Global => environment/global}/GlobalEnvironment.cpp (100%) rename src/{Environment/Global => environment/global}/GlobalEnvironment.h (100%) rename src/{Environment/Global => environment/global}/GnssSatellites.cpp (99%) rename src/{Environment/Global => environment/global}/GnssSatellites.h (100%) rename src/{Environment/Global => environment/global}/HipparcosCatalogue.cpp (100%) rename src/{Environment/Global => environment/global}/HipparcosCatalogue.h (100%) rename src/{Environment/Global => environment/global}/InitGlobalEnvironment.cpp (99%) rename src/{Environment/Global => environment/global}/InitGlobalEnvironment.hpp (83%) rename src/{Environment/Global => environment/global}/InitGnssSatellites.cpp (100%) rename src/{Environment/Global => environment/global}/InitGnssSatellites.hpp (86%) rename src/{Environment/Global => environment/global}/PhysicalConstants.hpp (100%) rename src/{Environment/Global => environment/global}/SimTime.cpp (100%) rename src/{Environment/Global => environment/global}/SimTime.h (100%) rename src/{Environment/Local => environment/local}/Atmosphere.cpp (100%) rename src/{Environment/Local => environment/local}/Atmosphere.h (100%) rename src/{Environment/Local => environment/local}/CMakeLists.txt (100%) rename src/{Environment/Local => environment/local}/InitLocalEnvironment.cpp (100%) rename src/{Environment/Local => environment/local}/InitLocalEnvironment.hpp (85%) rename src/{Environment/Local => environment/local}/LocalCelestialInformation.cpp (100%) rename src/{Environment/Local => environment/local}/LocalCelestialInformation.h (99%) rename src/{Environment/Local => environment/local}/LocalEnvironment.cpp (100%) rename src/{Environment/Local => environment/local}/LocalEnvironment.h (97%) rename src/{Environment/Local => environment/local}/MagEnvironment.cpp (100%) rename src/{Environment/Local => environment/local}/MagEnvironment.h (100%) rename src/{Environment/Local => environment/local}/SRPEnvironment.cpp (98%) rename src/{Environment/Local => environment/local}/SRPEnvironment.h (98%) diff --git a/CMakeLists.txt b/CMakeLists.txt index c28dc2e6b..6c080935f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,8 +64,8 @@ include_directories(${NRLMSISE00_DIR}/src) ## add_subdirectories add_subdirectory(src/simulation) -add_subdirectory(src/Environment/Global) -add_subdirectory(src/Environment/Local) +add_subdirectory(src/environment/global) +add_subdirectory(src/environment/local) add_subdirectory(src/Dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/Component) diff --git a/src/Component/AOCS/GNSSReceiver.cpp b/src/Component/AOCS/GNSSReceiver.cpp index c06fb11d0..047b85207 100644 --- a/src/Component/AOCS/GNSSReceiver.cpp +++ b/src/Component/AOCS/GNSSReceiver.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index a89fe5ce1..d2239a616 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -6,8 +6,8 @@ #pragma once #include -#include -#include +#include +#include #include #include diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index 9f581568c..d3b3ad7b2 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,7 +6,7 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index 241c82b6f..a4c8a1f24 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,7 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index c00727536..b147f36c0 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index 3064bc4e4..41d47fd02 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -9,7 +9,7 @@ #define __STT_H__ #include -#include +#include #include #include diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index c5ea224f2..14bae5d0a 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,8 +6,8 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include -#include +#include +#include #include #include diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 74257c082..50332ffa8 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/CommGS/GScalculator.cpp b/src/Component/CommGS/GScalculator.cpp index 16803e6a9..d4e85dc8c 100644 --- a/src/Component/CommGS/GScalculator.cpp +++ b/src/Component/CommGS/GScalculator.cpp @@ -5,7 +5,7 @@ #include "GScalculator.h" -#include +#include #include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 10bf0c66c..2b62dbcf3 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index 81caa1da5..e262e8e52 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -6,8 +6,8 @@ #pragma once #include #include -#include -#include +#include +#include #include #include diff --git a/src/Component/Power/PCU_InitialStudy.cpp b/src/Component/Power/PCU_InitialStudy.cpp index c0f1566c8..947972068 100644 --- a/src/Component/Power/PCU_InitialStudy.cpp +++ b/src/Component/Power/PCU_InitialStudy.cpp @@ -6,7 +6,7 @@ #include "PCU_InitialStudy.h" #include -#include +#include #include diff --git a/src/Component/Power/SAP.cpp b/src/Component/Power/SAP.cpp index 7217cb11d..fa2ccfae3 100644 --- a/src/Component/Power/SAP.cpp +++ b/src/Component/Power/SAP.cpp @@ -1,7 +1,7 @@ #include "SAP.h" #include -#include +#include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index 225aecb1a..e20e89bf5 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,8 +4,8 @@ */ #pragma once -#include -#include +#include +#include #include #include diff --git a/src/Dynamics/Attitude/ControlledAttitude.h b/src/Dynamics/Attitude/ControlledAttitude.h index 5dc64e1f0..48e06116c 100644 --- a/src/Dynamics/Attitude/ControlledAttitude.h +++ b/src/Dynamics/Attitude/ControlledAttitude.h @@ -5,7 +5,7 @@ #ifndef __controlled_attitude_H__ #define __controlled_attitude_H__ -#include +#include #include diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index b2a0152a9..222cb7a77 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -15,8 +15,8 @@ using libra::Vector; #include #include -#include "../Environment/Global/SimTime.h" -#include "../Environment/Local/LocalCelestialInformation.h" +#include "../environment/global/SimTime.h" +#include "../environment/local/LocalCelestialInformation.h" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" #include "./Orbit/Orbit.h" diff --git a/src/Dynamics/Orbit/Orbit.h b/src/Dynamics/Orbit/Orbit.h index fbdd876db..23241b16c 100644 --- a/src/Dynamics/Orbit/Orbit.h +++ b/src/Dynamics/Orbit/Orbit.h @@ -15,10 +15,10 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include -#include +#include #include /** diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.h b/src/Dynamics/Orbit/Rk4OrbitPropagation.h index 0f43db05d..22c008ba5 100644 --- a/src/Dynamics/Orbit/Rk4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Rk4OrbitPropagation.h @@ -2,7 +2,7 @@ * @file Rk4OrbitPropagation.h * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -#include +#include #include diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h index a3e5f0914..8ef794815 100644 --- a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h @@ -3,7 +3,7 @@ * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ #pragma once -#include +#include #include #include diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index e964cdc44..d032c054c 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -1,6 +1,6 @@ #include "InitTemperature.hpp" -#include +#include #include #include diff --git a/src/Dynamics/Thermal/Node.cpp b/src/Dynamics/Thermal/Node.cpp index 2b1b140be..135102f6b 100644 --- a/src/Dynamics/Thermal/Node.cpp +++ b/src/Dynamics/Thermal/Node.cpp @@ -1,6 +1,6 @@ #include "Node.h" -#include +#include #include using namespace std; diff --git a/src/Library/Geodesy/GeodeticPosition.cpp b/src/Library/Geodesy/GeodeticPosition.cpp index 521574b53..cc0b5e456 100644 --- a/src/Library/Geodesy/GeodeticPosition.cpp +++ b/src/Library/Geodesy/GeodeticPosition.cpp @@ -6,7 +6,7 @@ #include // TODO: do not to use the functions in SGP4 library -#include +#include #include #include diff --git a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp index dc8f8eac4..18483efa3 100644 --- a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp +++ b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp @@ -12,7 +12,7 @@ extern "C" { } #include /* for malloc/free */ -#include +#include #include #include #include diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index 2d1ec1df6..fac2b33db 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -7,7 +7,7 @@ #define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ #include "../Dynamics/Dynamics.h" -#include "../Environment/Local/LocalEnvironment.h" +#include "../environment/local/LocalEnvironment.h" #include "disturbance.hpp" /** diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 8d1e9a89d..999a7a36f 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,7 +5,7 @@ #include "air_drag.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 4dbcc2a06..a5c9793d3 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../Environment/Local/Atmosphere.h" +#include "../environment/local/Atmosphere.h" #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 202ef8c45..16c2e4767 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -8,7 +8,7 @@ #include -#include "../Environment/Global/SimTime.h" +#include "../environment/global/SimTime.h" #include "../simulation/spacecraft/structure/structure.hpp" #include "simple_disturbance.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index e6161704f..000e57745 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -5,7 +5,7 @@ #include "geopotential.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 98ff42fa8..fcd92e878 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -5,7 +5,7 @@ #include "gravity_gradient.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 592092211..d191d66c7 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -9,7 +9,7 @@ #define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ #include "../Dynamics/Dynamics.h" -#include "../Environment/Local/LocalEnvironment.h" +#include "../environment/local/LocalEnvironment.h" #include "disturbance.hpp" /** diff --git a/src/Environment/Global/CMakeLists.txt b/src/environment/global/CMakeLists.txt similarity index 100% rename from src/Environment/Global/CMakeLists.txt rename to src/environment/global/CMakeLists.txt diff --git a/src/Environment/Global/CelestialInformation.cpp b/src/environment/global/CelestialInformation.cpp similarity index 100% rename from src/Environment/Global/CelestialInformation.cpp rename to src/environment/global/CelestialInformation.cpp diff --git a/src/Environment/Global/CelestialInformation.h b/src/environment/global/CelestialInformation.h similarity index 100% rename from src/Environment/Global/CelestialInformation.h rename to src/environment/global/CelestialInformation.h diff --git a/src/Environment/Global/CelestialRotation.cpp b/src/environment/global/CelestialRotation.cpp similarity index 100% rename from src/Environment/Global/CelestialRotation.cpp rename to src/environment/global/CelestialRotation.cpp diff --git a/src/Environment/Global/CelestialRotation.h b/src/environment/global/CelestialRotation.h similarity index 100% rename from src/Environment/Global/CelestialRotation.h rename to src/environment/global/CelestialRotation.h diff --git a/src/Environment/Global/ClockGenerator.cpp b/src/environment/global/ClockGenerator.cpp similarity index 100% rename from src/Environment/Global/ClockGenerator.cpp rename to src/environment/global/ClockGenerator.cpp diff --git a/src/Environment/Global/ClockGenerator.h b/src/environment/global/ClockGenerator.h similarity index 100% rename from src/Environment/Global/ClockGenerator.h rename to src/environment/global/ClockGenerator.h diff --git a/src/Environment/Global/GlobalEnvironment.cpp b/src/environment/global/GlobalEnvironment.cpp similarity index 100% rename from src/Environment/Global/GlobalEnvironment.cpp rename to src/environment/global/GlobalEnvironment.cpp diff --git a/src/Environment/Global/GlobalEnvironment.h b/src/environment/global/GlobalEnvironment.h similarity index 100% rename from src/Environment/Global/GlobalEnvironment.h rename to src/environment/global/GlobalEnvironment.h diff --git a/src/Environment/Global/GnssSatellites.cpp b/src/environment/global/GnssSatellites.cpp similarity index 99% rename from src/Environment/Global/GnssSatellites.cpp rename to src/environment/global/GnssSatellites.cpp index 3f8c4c9ce..36ff55d83 100644 --- a/src/Environment/Global/GnssSatellites.cpp +++ b/src/environment/global/GnssSatellites.cpp @@ -9,7 +9,7 @@ #include //for jday() #include //for gstime() -#include +#include #include #include #include diff --git a/src/Environment/Global/GnssSatellites.h b/src/environment/global/GnssSatellites.h similarity index 100% rename from src/Environment/Global/GnssSatellites.h rename to src/environment/global/GnssSatellites.h diff --git a/src/Environment/Global/HipparcosCatalogue.cpp b/src/environment/global/HipparcosCatalogue.cpp similarity index 100% rename from src/Environment/Global/HipparcosCatalogue.cpp rename to src/environment/global/HipparcosCatalogue.cpp diff --git a/src/Environment/Global/HipparcosCatalogue.h b/src/environment/global/HipparcosCatalogue.h similarity index 100% rename from src/Environment/Global/HipparcosCatalogue.h rename to src/environment/global/HipparcosCatalogue.h diff --git a/src/Environment/Global/InitGlobalEnvironment.cpp b/src/environment/global/InitGlobalEnvironment.cpp similarity index 99% rename from src/Environment/Global/InitGlobalEnvironment.cpp rename to src/environment/global/InitGlobalEnvironment.cpp index 17c02c2ce..f82f664e8 100644 --- a/src/Environment/Global/InitGlobalEnvironment.cpp +++ b/src/environment/global/InitGlobalEnvironment.cpp @@ -4,7 +4,7 @@ */ #include "InitGlobalEnvironment.hpp" -#include +#include #include #include diff --git a/src/Environment/Global/InitGlobalEnvironment.hpp b/src/environment/global/InitGlobalEnvironment.hpp similarity index 83% rename from src/Environment/Global/InitGlobalEnvironment.hpp rename to src/environment/global/InitGlobalEnvironment.hpp index 97ae28149..d9a6ee0a1 100644 --- a/src/Environment/Global/InitGlobalEnvironment.hpp +++ b/src/environment/global/InitGlobalEnvironment.hpp @@ -5,9 +5,9 @@ #pragma once -#include -#include -#include +#include +#include +#include /** *@fn InitSimTime diff --git a/src/Environment/Global/InitGnssSatellites.cpp b/src/environment/global/InitGnssSatellites.cpp similarity index 100% rename from src/Environment/Global/InitGnssSatellites.cpp rename to src/environment/global/InitGnssSatellites.cpp diff --git a/src/Environment/Global/InitGnssSatellites.hpp b/src/environment/global/InitGnssSatellites.hpp similarity index 86% rename from src/Environment/Global/InitGnssSatellites.hpp rename to src/environment/global/InitGnssSatellites.hpp index 29ff7da3c..c7c95ab91 100644 --- a/src/Environment/Global/InitGnssSatellites.hpp +++ b/src/environment/global/InitGnssSatellites.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** *@fn InitGnssSatellites diff --git a/src/Environment/Global/PhysicalConstants.hpp b/src/environment/global/PhysicalConstants.hpp similarity index 100% rename from src/Environment/Global/PhysicalConstants.hpp rename to src/environment/global/PhysicalConstants.hpp diff --git a/src/Environment/Global/SimTime.cpp b/src/environment/global/SimTime.cpp similarity index 100% rename from src/Environment/Global/SimTime.cpp rename to src/environment/global/SimTime.cpp diff --git a/src/Environment/Global/SimTime.h b/src/environment/global/SimTime.h similarity index 100% rename from src/Environment/Global/SimTime.h rename to src/environment/global/SimTime.h diff --git a/src/Environment/Local/Atmosphere.cpp b/src/environment/local/Atmosphere.cpp similarity index 100% rename from src/Environment/Local/Atmosphere.cpp rename to src/environment/local/Atmosphere.cpp diff --git a/src/Environment/Local/Atmosphere.h b/src/environment/local/Atmosphere.h similarity index 100% rename from src/Environment/Local/Atmosphere.h rename to src/environment/local/Atmosphere.h diff --git a/src/Environment/Local/CMakeLists.txt b/src/environment/local/CMakeLists.txt similarity index 100% rename from src/Environment/Local/CMakeLists.txt rename to src/environment/local/CMakeLists.txt diff --git a/src/Environment/Local/InitLocalEnvironment.cpp b/src/environment/local/InitLocalEnvironment.cpp similarity index 100% rename from src/Environment/Local/InitLocalEnvironment.cpp rename to src/environment/local/InitLocalEnvironment.cpp diff --git a/src/Environment/Local/InitLocalEnvironment.hpp b/src/environment/local/InitLocalEnvironment.hpp similarity index 85% rename from src/Environment/Local/InitLocalEnvironment.hpp rename to src/environment/local/InitLocalEnvironment.hpp index c82c936fb..90e06edd4 100644 --- a/src/Environment/Local/InitLocalEnvironment.hpp +++ b/src/environment/local/InitLocalEnvironment.hpp @@ -4,9 +4,9 @@ */ #pragma once -#include -#include -#include +#include +#include +#include /** * @fn InitMagEnvironment diff --git a/src/Environment/Local/LocalCelestialInformation.cpp b/src/environment/local/LocalCelestialInformation.cpp similarity index 100% rename from src/Environment/Local/LocalCelestialInformation.cpp rename to src/environment/local/LocalCelestialInformation.cpp diff --git a/src/Environment/Local/LocalCelestialInformation.h b/src/environment/local/LocalCelestialInformation.h similarity index 99% rename from src/Environment/Local/LocalCelestialInformation.h rename to src/environment/local/LocalCelestialInformation.h index 001e674e5..7c1491fff 100644 --- a/src/Environment/Local/LocalCelestialInformation.h +++ b/src/environment/local/LocalCelestialInformation.h @@ -6,7 +6,7 @@ #ifndef __local_celestial_information_H__ #define __local_celestial_information_H__ -#include "../Global/CelestialInformation.h" +#include "../global/CelestialInformation.h" /** * @class LocalCelestialInformation diff --git a/src/Environment/Local/LocalEnvironment.cpp b/src/environment/local/LocalEnvironment.cpp similarity index 100% rename from src/Environment/Local/LocalEnvironment.cpp rename to src/environment/local/LocalEnvironment.cpp diff --git a/src/Environment/Local/LocalEnvironment.h b/src/environment/local/LocalEnvironment.h similarity index 97% rename from src/Environment/Local/LocalEnvironment.h rename to src/environment/local/LocalEnvironment.h index 9c427e209..659c1e2cc 100644 --- a/src/Environment/Local/LocalEnvironment.h +++ b/src/environment/local/LocalEnvironment.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include "Atmosphere.h" #include "LocalCelestialInformation.h" diff --git a/src/Environment/Local/MagEnvironment.cpp b/src/environment/local/MagEnvironment.cpp similarity index 100% rename from src/Environment/Local/MagEnvironment.cpp rename to src/environment/local/MagEnvironment.cpp diff --git a/src/Environment/Local/MagEnvironment.h b/src/environment/local/MagEnvironment.h similarity index 100% rename from src/Environment/Local/MagEnvironment.h rename to src/environment/local/MagEnvironment.h diff --git a/src/Environment/Local/SRPEnvironment.cpp b/src/environment/local/SRPEnvironment.cpp similarity index 98% rename from src/Environment/Local/SRPEnvironment.cpp rename to src/environment/local/SRPEnvironment.cpp index 77fdc9a74..d21160b3b 100644 --- a/src/Environment/Local/SRPEnvironment.cpp +++ b/src/environment/local/SRPEnvironment.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include #include #include diff --git a/src/Environment/Local/SRPEnvironment.h b/src/environment/local/SRPEnvironment.h similarity index 98% rename from src/Environment/Local/SRPEnvironment.h rename to src/environment/local/SRPEnvironment.h index fb4caf296..b8eb3c79b 100644 --- a/src/Environment/Local/SRPEnvironment.h +++ b/src/environment/local/SRPEnvironment.h @@ -4,7 +4,7 @@ */ #ifndef __SRPEnvironment_h__ #define __SRPEnvironment_h__ -#include +#include #include #include diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index e01e3dd24..dfb3a1b0b 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include +#include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 48083c95f..b9e5ff1fc 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index a2e0b220d..23f8deb49 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 6c34c485c..a5f9ba38c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 847ad0ba5..c7708293a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,7 +5,7 @@ #include "sample_spacecraft.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 07e6449fe..f7f11ec34 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -7,8 +7,8 @@ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #include -#include -#include +#include +#include #include #include From 5c4f1687772acd73a743e8aa08c2c3d1638f7a49 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:02:43 +0100 Subject: [PATCH 0217/1086] Renamce CelestialInformation --- src/Dynamics/Orbit/Orbit.h | 2 +- src/Dynamics/Orbit/Rk4OrbitPropagation.h | 2 +- src/Dynamics/Orbit/Sgp4OrbitPropagation.h | 2 +- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/GlobalEnvironment.h | 2 +- src/environment/global/InitGlobalEnvironment.hpp | 2 +- ...CelestialInformation.cpp => celestial_information.cpp} | 4 ++-- .../{CelestialInformation.h => celestial_information.hpp} | 8 ++++---- src/environment/local/LocalCelestialInformation.h | 2 +- 9 files changed, 13 insertions(+), 13 deletions(-) rename src/environment/global/{CelestialInformation.cpp => celestial_information.cpp} (99%) rename src/environment/global/{CelestialInformation.h => celestial_information.hpp} (97%) diff --git a/src/Dynamics/Orbit/Orbit.h b/src/Dynamics/Orbit/Orbit.h index 23241b16c..a625e5f62 100644 --- a/src/Dynamics/Orbit/Orbit.h +++ b/src/Dynamics/Orbit/Orbit.h @@ -15,7 +15,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.h b/src/Dynamics/Orbit/Rk4OrbitPropagation.h index 22c008ba5..76d14429b 100644 --- a/src/Dynamics/Orbit/Rk4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Rk4OrbitPropagation.h @@ -2,7 +2,7 @@ * @file Rk4OrbitPropagation.h * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -#include +#include #include diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h index 8ef794815..ca67a50ed 100644 --- a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h @@ -3,7 +3,7 @@ * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ #pragma once -#include +#include #include #include diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index e1e1f4aea..e35f2e957 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC GlobalEnvironment.cpp - CelestialInformation.cpp + celestial_information.cpp HipparcosCatalogue.cpp GnssSatellites.cpp SimTime.cpp diff --git a/src/environment/global/GlobalEnvironment.h b/src/environment/global/GlobalEnvironment.h index 5da37477b..e198a2aa1 100644 --- a/src/environment/global/GlobalEnvironment.h +++ b/src/environment/global/GlobalEnvironment.h @@ -9,7 +9,7 @@ #include -#include "CelestialInformation.h" +#include "celestial_information.hpp" #include "GnssSatellites.h" #include "HipparcosCatalogue.h" #include "SimTime.h" diff --git a/src/environment/global/InitGlobalEnvironment.hpp b/src/environment/global/InitGlobalEnvironment.hpp index d9a6ee0a1..aacaa9d88 100644 --- a/src/environment/global/InitGlobalEnvironment.hpp +++ b/src/environment/global/InitGlobalEnvironment.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include #include diff --git a/src/environment/global/CelestialInformation.cpp b/src/environment/global/celestial_information.cpp similarity index 99% rename from src/environment/global/CelestialInformation.cpp rename to src/environment/global/celestial_information.cpp index c164b06ae..575929d7e 100644 --- a/src/environment/global/CelestialInformation.cpp +++ b/src/environment/global/celestial_information.cpp @@ -1,10 +1,10 @@ /** - * @file CelestialInformation.cpp + * @file celestial_information.cpp * @brief Class to manage the information related with the celestial bodies * @details This class uses SPICE to get the information of celestial bodies */ -#include "CelestialInformation.h" +#include "celestial_information.hpp" #include #include diff --git a/src/environment/global/CelestialInformation.h b/src/environment/global/celestial_information.hpp similarity index 97% rename from src/environment/global/CelestialInformation.h rename to src/environment/global/celestial_information.hpp index 5caf6aca8..91302dd4c 100644 --- a/src/environment/global/CelestialInformation.h +++ b/src/environment/global/celestial_information.hpp @@ -1,11 +1,11 @@ /** - * @file CelestialInformation.h + * @file celestial_information.hpp * @brief Class to manage the information related with the celestial bodies * @details This class uses SPICE to get the information of celestial bodies */ -#ifndef __celestial_information_H__ -#define __celestial_information_H__ +#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ +#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ #include #include @@ -199,4 +199,4 @@ class CelestialInformation : public ILoggable { void GetPlanetOrbit(const char* planet_name, double et, double orbit[6]); }; -#endif //__celestial_information_H__ +#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ diff --git a/src/environment/local/LocalCelestialInformation.h b/src/environment/local/LocalCelestialInformation.h index 7c1491fff..7d70fae68 100644 --- a/src/environment/local/LocalCelestialInformation.h +++ b/src/environment/local/LocalCelestialInformation.h @@ -6,7 +6,7 @@ #ifndef __local_celestial_information_H__ #define __local_celestial_information_H__ -#include "../global/CelestialInformation.h" +#include "../global/celestial_information.hpp" /** * @class LocalCelestialInformation From 64bae172f3a846ea4fa1c7234bae47e90ef15af1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:05:55 +0100 Subject: [PATCH 0218/1086] Rename CelestialRotation --- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/celestial_information.hpp | 2 +- .../{CelestialRotation.cpp => celestial_rotation.cpp} | 4 ++-- .../{CelestialRotation.h => celestial_rotation.hpp} | 8 ++++---- src/simulation/ground_station/ground_station.hpp | 2 +- 5 files changed, 9 insertions(+), 9 deletions(-) rename src/environment/global/{CelestialRotation.cpp => celestial_rotation.cpp} (99%) rename src/environment/global/{CelestialRotation.h => celestial_rotation.hpp} (96%) diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index e35f2e957..6eb5c3afc 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -8,7 +8,7 @@ add_library(${PROJECT_NAME} STATIC GnssSatellites.cpp SimTime.cpp ClockGenerator.cpp - CelestialRotation.cpp + celestial_rotation.cpp InitGlobalEnvironment.cpp InitGnssSatellites.cpp ) diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 91302dd4c..7306de4e9 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,12 +10,12 @@ #include #include -#include "CelestialRotation.h" #include "Interface/LogOutput/ILoggable.h" #include "Library/math/MatVec.hpp" #include "Library/math/Matrix.hpp" #include "Library/math/Quaternion.hpp" #include "Library/math/Vector.hpp" +#include "celestial_rotation.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/environment/global/CelestialRotation.cpp b/src/environment/global/celestial_rotation.cpp similarity index 99% rename from src/environment/global/CelestialRotation.cpp rename to src/environment/global/celestial_rotation.cpp index 93aa13019..1fec2b871 100644 --- a/src/environment/global/CelestialRotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -1,5 +1,5 @@ /** - * @file CelestialRotation.cpp + * @file celestial_rotation.cpp * @brief Class to calculate the celestial rotation * @note Support earth rotation only now (TODO: add other planets) * Refs: 福島,"天体の回転運動理論入門講義ノート", 2007 (in Japanese), @@ -7,7 +7,7 @@ * IERS Conventions 2003 */ -#include "CelestialRotation.h" +#include "celestial_rotation.hpp" #include // for jday() #include // for gstime() diff --git a/src/environment/global/CelestialRotation.h b/src/environment/global/celestial_rotation.hpp similarity index 96% rename from src/environment/global/CelestialRotation.h rename to src/environment/global/celestial_rotation.hpp index be0303f69..7177141c3 100644 --- a/src/environment/global/CelestialRotation.h +++ b/src/environment/global/celestial_rotation.hpp @@ -1,5 +1,5 @@ /** - * @file CelestialRotation.h + * @file celestial_rotation.hpp * @brief Class to calculate the celestial rotation * @note Support earth rotation only now (TODO: add other planets) * Refs: 福島,"天体の回転運動理論入門講義ノート", 2007 (in Japanese), @@ -7,8 +7,8 @@ * IERS Conventions 2003 */ -#ifndef __celestial_rotation_H__ -#define __celestial_rotation_H__ +#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ +#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #include @@ -112,4 +112,4 @@ class CelestialRotation { const double kDayJulianCentury = 36525; //!< Conversion constant from Julian century to day [day/century] }; -#endif //__celestial_rotation_H__ +#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 23f8deb49..eb53961c6 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include +#include #include #include From 2e61cf35dfee08b93714aa879b6d91e99af35540 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:08:40 +0100 Subject: [PATCH 0219/1086] Rename ClockGenerator --- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/Power/PCU_InitialStudy.cpp | 2 +- src/Component/Power/SAP.cpp | 2 +- src/environment/global/CMakeLists.txt | 2 +- .../global/{ClockGenerator.cpp => clock_generator.cpp} | 4 ++-- .../global/{ClockGenerator.h => clock_generator.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- 8 files changed, 14 insertions(+), 10 deletions(-) rename src/environment/global/{ClockGenerator.cpp => clock_generator.cpp} (94%) rename src/environment/global/{ClockGenerator.h => clock_generator.hpp} (88%) diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 50332ffa8..42a612808 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Power/PCU_InitialStudy.cpp b/src/Component/Power/PCU_InitialStudy.cpp index 947972068..a4f73151c 100644 --- a/src/Component/Power/PCU_InitialStudy.cpp +++ b/src/Component/Power/PCU_InitialStudy.cpp @@ -6,7 +6,7 @@ #include "PCU_InitialStudy.h" #include -#include +#include #include diff --git a/src/Component/Power/SAP.cpp b/src/Component/Power/SAP.cpp index fa2ccfae3..0a78b7aea 100644 --- a/src/Component/Power/SAP.cpp +++ b/src/Component/Power/SAP.cpp @@ -1,7 +1,7 @@ #include "SAP.h" #include -#include +#include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index 6eb5c3afc..4b7ba3dd5 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -7,7 +7,7 @@ add_library(${PROJECT_NAME} STATIC HipparcosCatalogue.cpp GnssSatellites.cpp SimTime.cpp - ClockGenerator.cpp + clock_generator.cpp celestial_rotation.cpp InitGlobalEnvironment.cpp InitGnssSatellites.cpp diff --git a/src/environment/global/ClockGenerator.cpp b/src/environment/global/clock_generator.cpp similarity index 94% rename from src/environment/global/ClockGenerator.cpp rename to src/environment/global/clock_generator.cpp index 51874b7a1..edb3d4884 100644 --- a/src/environment/global/ClockGenerator.cpp +++ b/src/environment/global/clock_generator.cpp @@ -1,9 +1,9 @@ /** - * @file ClockGenerator.cpp + * @file clock_generator.cpp * @brief Class to generate clock for classes which have ITickable */ -#include "ClockGenerator.h" +#include "clock_generator.hpp" ClockGenerator::~ClockGenerator() {} diff --git a/src/environment/global/ClockGenerator.h b/src/environment/global/clock_generator.hpp similarity index 88% rename from src/environment/global/ClockGenerator.h rename to src/environment/global/clock_generator.hpp index f4b3bfd7d..603f4f2ce 100644 --- a/src/environment/global/ClockGenerator.h +++ b/src/environment/global/clock_generator.hpp @@ -1,9 +1,11 @@ /** - * @file ClockGenerator.h + * @file clock_generator.hpp * @brief Class to generate clock for classes which have ITickable */ -#pragma once +#ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ +#define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ + #include #include @@ -57,3 +59,5 @@ class ClockGenerator { std::vector components_; //!< Component list fot tick int timer_count_; //!< Timer count TODO: consider size, unsigned }; + +#endif // S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index c7708293a..24dcbfbfb 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,7 +5,7 @@ #include "sample_spacecraft.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index f7f11ec34..27d43dd79 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #include -#include +#include #include #include From 06ae70a0b5c03e1f0767bc9378b31722dfe66b4f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:13:51 +0100 Subject: [PATCH 0220/1086] Rename GlobalEnvironment --- src/Component/CommGS/GScalculator.h | 2 +- src/environment/global/CMakeLists.txt | 2 +- .../{GlobalEnvironment.cpp => global_environment.cpp} | 4 ++-- .../{GlobalEnvironment.h => global_environment.hpp} | 9 ++++++--- src/environment/local/LocalEnvironment.h | 2 +- src/simulation/case/simulation_case.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 2 +- 7 files changed, 13 insertions(+), 10 deletions(-) rename src/environment/global/{GlobalEnvironment.cpp => global_environment.cpp} (95%) rename src/environment/global/{GlobalEnvironment.h => global_environment.hpp} (91%) diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 2b62dbcf3..ecaf55a5d 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index 4b7ba3dd5..ec59cf319 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -2,7 +2,7 @@ project(GLOBAL_ENVIRONMENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - GlobalEnvironment.cpp + global_environment.cpp celestial_information.cpp HipparcosCatalogue.cpp GnssSatellites.cpp diff --git a/src/environment/global/GlobalEnvironment.cpp b/src/environment/global/global_environment.cpp similarity index 95% rename from src/environment/global/GlobalEnvironment.cpp rename to src/environment/global/global_environment.cpp index c79afcf70..ca0da8b52 100644 --- a/src/environment/global/GlobalEnvironment.cpp +++ b/src/environment/global/global_environment.cpp @@ -1,9 +1,9 @@ /** - * @file GlobalEnvironment.cpp + * @file global_environment.cpp * @brief Class to manage the global environment */ -#include "GlobalEnvironment.h" +#include "global_environment.hpp" #include diff --git a/src/environment/global/GlobalEnvironment.h b/src/environment/global/global_environment.hpp similarity index 91% rename from src/environment/global/GlobalEnvironment.h rename to src/environment/global/global_environment.hpp index e198a2aa1..da553db1d 100644 --- a/src/environment/global/GlobalEnvironment.h +++ b/src/environment/global/global_environment.hpp @@ -1,18 +1,19 @@ /** - * @file GlobalEnvironment.h + * @file global_environment.hpp * @brief Class to manage the global environment */ -#pragma once +#ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ +#define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ #include #include -#include "celestial_information.hpp" #include "GnssSatellites.h" #include "HipparcosCatalogue.h" #include "SimTime.h" +#include "celestial_information.hpp" /** * @class GlobalEnvironment @@ -82,3 +83,5 @@ class GlobalEnvironment { HipparcosCatalogue* hipp_; //!< Hipparcos catalogue GnssSatellites* gnss_satellites_; //!< GNSS satellites }; + +#endif // S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ diff --git a/src/environment/local/LocalEnvironment.h b/src/environment/local/LocalEnvironment.h index 659c1e2cc..7638d91ae 100644 --- a/src/environment/local/LocalEnvironment.h +++ b/src/environment/local/LocalEnvironment.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include "Atmosphere.h" #include "LocalCelestialInformation.h" diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index dfb3a1b0b..ec0af7811 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index a5f9ba38c..2f760f5d2 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include From 5b586a7f9e6719328030066e5114458d86dc9fe6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:31:54 +0100 Subject: [PATCH 0221/1086] Rename GnssSatellites --- src/Component/AOCS/GNSSReceiver.h | 2 +- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/InitGnssSatellites.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- .../global/{GnssSatellites.cpp => gnss_satellites.cpp} | 6 +++--- .../global/{GnssSatellites.h => gnss_satellites.hpp} | 9 +++++---- 6 files changed, 12 insertions(+), 11 deletions(-) rename src/environment/global/{GnssSatellites.cpp => gnss_satellites.cpp} (99%) rename src/environment/global/{GnssSatellites.h => gnss_satellites.hpp} (99%) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index d2239a616..4aec4c159 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index ec59cf319..c56d06dd0 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC global_environment.cpp celestial_information.cpp HipparcosCatalogue.cpp - GnssSatellites.cpp + gnss_satellites.cpp SimTime.cpp clock_generator.cpp celestial_rotation.cpp diff --git a/src/environment/global/InitGnssSatellites.hpp b/src/environment/global/InitGnssSatellites.hpp index c7c95ab91..79a87cd83 100644 --- a/src/environment/global/InitGnssSatellites.hpp +++ b/src/environment/global/InitGnssSatellites.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** *@fn InitGnssSatellites diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index da553db1d..2de14a628 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -10,7 +10,7 @@ #include -#include "GnssSatellites.h" +#include "gnss_satellites.hpp" #include "HipparcosCatalogue.h" #include "SimTime.h" #include "celestial_information.hpp" diff --git a/src/environment/global/GnssSatellites.cpp b/src/environment/global/gnss_satellites.cpp similarity index 99% rename from src/environment/global/GnssSatellites.cpp rename to src/environment/global/gnss_satellites.cpp index 36ff55d83..adebb5c12 100644 --- a/src/environment/global/GnssSatellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -1,18 +1,18 @@ /** - * @file GnssSatellites + * @file gnss_satellites.cpp * @brief Class to calculate GNSS satellite position and related states */ -#include "GnssSatellites.h" +#include "gnss_satellites.hpp" #include #include //for jday() #include //for gstime() -#include #include #include #include +#include #include #include #include diff --git a/src/environment/global/GnssSatellites.h b/src/environment/global/gnss_satellites.hpp similarity index 99% rename from src/environment/global/GnssSatellites.h rename to src/environment/global/gnss_satellites.hpp index cfa2ab415..c1f96bc75 100644 --- a/src/environment/global/GnssSatellites.h +++ b/src/environment/global/gnss_satellites.hpp @@ -1,10 +1,10 @@ /** - * @file GnssSatellites.h + * @file gnss_satellites.hpp * @brief Class to calculate GNSS satellite position and related states */ -#ifndef __gnss_satellites_h__ -#define __gnss_satellites_h__ +#ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ +#define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #include @@ -509,4 +509,5 @@ class GnssSatellites : public ILoggable { ofstream ofs_sa; //!< Debug output for difference between true and estimated value #endif }; -#endif + +#endif // S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ From a35c5a1d854d147c371c6a391b184d1ff9cb2b04 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:34:45 +0100 Subject: [PATCH 0222/1086] Rename HipparcosCatalogue --- src/Component/Mission/Telescope/Telescope.h | 2 +- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/InitGlobalEnvironment.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- .../{HipparcosCatalogue.cpp => hipparcos_catalogue.cpp} | 4 ++-- .../{HipparcosCatalogue.h => hipparcos_catalogue.hpp} | 9 +++++++-- 6 files changed, 13 insertions(+), 8 deletions(-) rename src/environment/global/{HipparcosCatalogue.cpp => hipparcos_catalogue.cpp} (96%) rename src/environment/global/{HipparcosCatalogue.h => hipparcos_catalogue.hpp} (94%) diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index e262e8e52..fb500210a 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -6,7 +6,7 @@ #pragma once #include #include -#include +#include #include #include diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index c56d06dd0..01a394cc5 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC global_environment.cpp celestial_information.cpp - HipparcosCatalogue.cpp + hipparcos_catalogue.cpp gnss_satellites.cpp SimTime.cpp clock_generator.cpp diff --git a/src/environment/global/InitGlobalEnvironment.hpp b/src/environment/global/InitGlobalEnvironment.hpp index aacaa9d88..62f286566 100644 --- a/src/environment/global/InitGlobalEnvironment.hpp +++ b/src/environment/global/InitGlobalEnvironment.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include +#include #include /** diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 2de14a628..dbac82b4c 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -11,7 +11,7 @@ #include #include "gnss_satellites.hpp" -#include "HipparcosCatalogue.h" +#include "hipparcos_catalogue.hpp" #include "SimTime.h" #include "celestial_information.hpp" diff --git a/src/environment/global/HipparcosCatalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp similarity index 96% rename from src/environment/global/HipparcosCatalogue.cpp rename to src/environment/global/hipparcos_catalogue.cpp index 67e7b3547..c146cf32c 100644 --- a/src/environment/global/HipparcosCatalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -1,8 +1,8 @@ /** - *@file HipparcosCatalogue.cpp + *@file hipparcos_catalogue.cpp *@brief Class to calculate star direction with Hipparcos catalogue */ -#include "HipparcosCatalogue.h" +#include "hipparcos_catalogue.hpp" #include #include diff --git a/src/environment/global/HipparcosCatalogue.h b/src/environment/global/hipparcos_catalogue.hpp similarity index 94% rename from src/environment/global/HipparcosCatalogue.h rename to src/environment/global/hipparcos_catalogue.hpp index dd2d3c89f..08c3c4f44 100644 --- a/src/environment/global/HipparcosCatalogue.h +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -1,8 +1,11 @@ /** - *@file HipparcosCatalogue.h + *@file hipparcos_catalogue.hpp *@brief Class to calculate star direction with Hipparcos catalogue */ -#pragma once + +#ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ +#define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ + #include #include @@ -108,3 +111,5 @@ class HipparcosCatalogue : public ILoggable { double max_magnitude_; //!< Maximum magnitude in the data base std::string catalogue_path_; //!< Path to Hipparcos catalog file }; + +#endif // S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ From 8497fe5fbb8cfa1cfd74a6f1dca8eab4e25bbe88 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:37:32 +0100 Subject: [PATCH 0223/1086] Rename InitGlobalEnvironment --- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/global_environment.cpp | 2 +- ...vironment.cpp => initialize_global_environment.cpp} | 6 +++--- ...vironment.hpp => initialize_global_environment.hpp} | 10 +++++++--- 4 files changed, 12 insertions(+), 8 deletions(-) rename src/environment/global/{InitGlobalEnvironment.cpp => initialize_global_environment.cpp} (98%) rename src/environment/global/{InitGlobalEnvironment.hpp => initialize_global_environment.hpp} (77%) diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index 01a394cc5..b391eefff 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(${PROJECT_NAME} STATIC SimTime.cpp clock_generator.cpp celestial_rotation.cpp - InitGlobalEnvironment.cpp + initialize_global_environment.cpp InitGnssSatellites.cpp ) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index ca0da8b52..168e272d3 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -7,7 +7,7 @@ #include -#include "InitGlobalEnvironment.hpp" +#include "initialize_global_environment.hpp" #include "InitGnssSatellites.hpp" GlobalEnvironment::GlobalEnvironment(SimulationConfig* sim_config) { Initialize(sim_config); } diff --git a/src/environment/global/InitGlobalEnvironment.cpp b/src/environment/global/initialize_global_environment.cpp similarity index 98% rename from src/environment/global/InitGlobalEnvironment.cpp rename to src/environment/global/initialize_global_environment.cpp index f82f664e8..5fbb22235 100644 --- a/src/environment/global/InitGlobalEnvironment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -1,12 +1,12 @@ /** - *@file InitGlobalEnvironment.cpp + *@file initialize_global_environment.cpp *@brief Initialize functions for classes in global environment */ -#include "InitGlobalEnvironment.hpp" +#include "initialize_global_environment.hpp" -#include #include #include +#include #include diff --git a/src/environment/global/InitGlobalEnvironment.hpp b/src/environment/global/initialize_global_environment.hpp similarity index 77% rename from src/environment/global/InitGlobalEnvironment.hpp rename to src/environment/global/initialize_global_environment.hpp index 62f286566..0ac21d5a0 100644 --- a/src/environment/global/InitGlobalEnvironment.hpp +++ b/src/environment/global/initialize_global_environment.hpp @@ -1,13 +1,15 @@ /** - *@file InitGlobalEnvironment.hpp + *@file initialize_global_environment.hpp *@brief Initialize functions for classes in global environment */ -#pragma once +#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ +#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ + +#include #include #include -#include /** *@fn InitSimTime @@ -29,3 +31,5 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name); *@param [in] file_name: Path to the initialize function */ CelestialInformation* InitCelesInfo(std::string file_name); + +#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ From 8baf56c08db07b8e89189a75954ddee448f25902 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:39:29 +0100 Subject: [PATCH 0224/1086] Rename InitGnssSatellites --- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/global_environment.cpp | 2 +- ...itGnssSatellites.cpp => initialize_gnss_satellites.cpp} | 4 ++-- ...itGnssSatellites.hpp => initialize_gnss_satellites.hpp} | 7 +++++-- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/environment/global/{InitGnssSatellites.cpp => initialize_gnss_satellites.cpp} (99%) rename src/environment/global/{InitGnssSatellites.hpp => initialize_gnss_satellites.hpp} (58%) diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index b391eefff..286fdb983 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -10,7 +10,7 @@ add_library(${PROJECT_NAME} STATIC clock_generator.cpp celestial_rotation.cpp initialize_global_environment.cpp - InitGnssSatellites.cpp + initialize_gnss_satellites.cpp ) include(../../../common.cmake) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 168e272d3..8816eda28 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -8,7 +8,7 @@ #include #include "initialize_global_environment.hpp" -#include "InitGnssSatellites.hpp" +#include "initialize_gnss_satellites.hpp" GlobalEnvironment::GlobalEnvironment(SimulationConfig* sim_config) { Initialize(sim_config); } diff --git a/src/environment/global/InitGnssSatellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp similarity index 99% rename from src/environment/global/InitGnssSatellites.cpp rename to src/environment/global/initialize_gnss_satellites.cpp index 7319dcb58..ffdb3643b 100644 --- a/src/environment/global/InitGnssSatellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -1,9 +1,9 @@ /** - *@file InitGnssSatellites.cpp + *@file initialize_gnss_satellites.cpp *@brief Initialize functions for GnssSatellites class */ -#include "InitGnssSatellites.hpp" +#include "initialize_gnss_satellites.hpp" #include diff --git a/src/environment/global/InitGnssSatellites.hpp b/src/environment/global/initialize_gnss_satellites.hpp similarity index 58% rename from src/environment/global/InitGnssSatellites.hpp rename to src/environment/global/initialize_gnss_satellites.hpp index 79a87cd83..f7b215fe6 100644 --- a/src/environment/global/InitGnssSatellites.hpp +++ b/src/environment/global/initialize_gnss_satellites.hpp @@ -1,9 +1,10 @@ /** - *@file InitGnssSatellites.hpp + *@file initialize_gnss_satellites.hpp *@brief Initialize functions for GnssSatellites class */ -#pragma once +#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ +#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ #include @@ -13,3 +14,5 @@ *@param [in] file_name: Path to the initialize function */ GnssSatellites* InitGnssSatellites(std::string file_name); + +#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ From 1fd9130348789cf0584f28c15022436c9badbc4e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:41:36 +0100 Subject: [PATCH 0225/1086] Rename PhysicalConstants --- src/Component/AOCS/GNSSReceiver.cpp | 2 +- src/Component/AOCS/STT.cpp | 2 +- src/Component/CommGS/GScalculator.cpp | 2 +- src/Dynamics/Orbit/Orbit.h | 2 +- src/Dynamics/Thermal/Node.cpp | 2 +- src/Library/Geodesy/GeodeticPosition.cpp | 2 +- src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- .../{PhysicalConstants.hpp => physical_constants.hpp} | 8 ++++---- src/environment/local/SRPEnvironment.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- 14 files changed, 17 insertions(+), 17 deletions(-) rename src/environment/global/{PhysicalConstants.hpp => physical_constants.hpp} (91%) diff --git a/src/Component/AOCS/GNSSReceiver.cpp b/src/Component/AOCS/GNSSReceiver.cpp index 047b85207..d2774dd65 100644 --- a/src/Component/AOCS/GNSSReceiver.cpp +++ b/src/Component/AOCS/GNSSReceiver.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index b147f36c0..5599c0058 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/Component/CommGS/GScalculator.cpp b/src/Component/CommGS/GScalculator.cpp index d4e85dc8c..85b9438b7 100644 --- a/src/Component/CommGS/GScalculator.cpp +++ b/src/Component/CommGS/GScalculator.cpp @@ -5,7 +5,7 @@ #include "GScalculator.h" -#include +#include #include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, diff --git a/src/Dynamics/Orbit/Orbit.h b/src/Dynamics/Orbit/Orbit.h index a625e5f62..9ff571bb7 100644 --- a/src/Dynamics/Orbit/Orbit.h +++ b/src/Dynamics/Orbit/Orbit.h @@ -18,7 +18,7 @@ using libra::Vector; #include #include -#include +#include #include /** diff --git a/src/Dynamics/Thermal/Node.cpp b/src/Dynamics/Thermal/Node.cpp index 135102f6b..cade38606 100644 --- a/src/Dynamics/Thermal/Node.cpp +++ b/src/Dynamics/Thermal/Node.cpp @@ -1,6 +1,6 @@ #include "Node.h" -#include +#include #include using namespace std; diff --git a/src/Library/Geodesy/GeodeticPosition.cpp b/src/Library/Geodesy/GeodeticPosition.cpp index cc0b5e456..8c59f6c93 100644 --- a/src/Library/Geodesy/GeodeticPosition.cpp +++ b/src/Library/Geodesy/GeodeticPosition.cpp @@ -6,7 +6,7 @@ #include // TODO: do not to use the functions in SGP4 library -#include +#include #include #include diff --git a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp index 18483efa3..779c7cd03 100644 --- a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp +++ b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp @@ -12,7 +12,7 @@ extern "C" { } #include /* for malloc/free */ -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 999a7a36f..c0799da6a 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,7 +5,7 @@ #include "air_drag.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 000e57745..e04e25f36 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -5,7 +5,7 @@ #include "geopotential.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index fcd92e878..c34bca564 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -5,7 +5,7 @@ #include "gravity_gradient.hpp" -#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index adebb5c12..4f3d60173 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/environment/global/PhysicalConstants.hpp b/src/environment/global/physical_constants.hpp similarity index 91% rename from src/environment/global/PhysicalConstants.hpp rename to src/environment/global/physical_constants.hpp index d818f7bab..28305190a 100644 --- a/src/environment/global/PhysicalConstants.hpp +++ b/src/environment/global/physical_constants.hpp @@ -1,10 +1,10 @@ /** - * @file + * @file physical_constants.hpp * @brief header for physical constant values */ -#ifndef PHYSICAL_CONSTANT_HPP_ -#define PHYSICAL_CONSTANT_HPP_ +#ifndef S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ +#define S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ #include // std::is_floating_point_v @@ -39,4 +39,4 @@ DEFINE_PHYSICAL_CONSTANT(earth_flattening, 3.352797e-3L) / } // namespace environment -#endif // PHYSICAL_CONSTANT_HPP_ +#endif // S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ diff --git a/src/environment/local/SRPEnvironment.cpp b/src/environment/local/SRPEnvironment.cpp index d21160b3b..e75ce790c 100644 --- a/src/environment/local/SRPEnvironment.cpp +++ b/src/environment/local/SRPEnvironment.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index b9e5ff1fc..aca879271 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include From 2759b3c80d3a27d5a79ff32735c0619b872637ac Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:43:19 +0100 Subject: [PATCH 0226/1086] Rename SimulationTime --- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Dynamics/Dynamics.h | 2 +- src/Dynamics/Thermal/InitTemperature.cpp | 2 +- src/disturbances/disturbances.hpp | 2 +- src/environment/global/CMakeLists.txt | 2 +- src/environment/global/clock_generator.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/initialize_global_environment.cpp | 2 +- src/environment/global/initialize_global_environment.hpp | 3 +-- .../global/{SimTime.cpp => simulation_time.cpp} | 4 ++-- src/environment/global/{SimTime.h => simulation_time.hpp} | 8 ++++---- 12 files changed, 16 insertions(+), 17 deletions(-) rename src/environment/global/{SimTime.cpp => simulation_time.cpp} (99%) rename src/environment/global/{SimTime.h => simulation_time.hpp} (98%) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 4aec4c159..8c497d63d 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index 222cb7a77..fb44400cf 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -15,7 +15,7 @@ using libra::Vector; #include #include -#include "../environment/global/SimTime.h" +#include "../environment/global/simulation_time.hpp" #include "../environment/local/LocalCelestialInformation.h" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index d032c054c..bd58876e7 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -1,6 +1,6 @@ #include "InitTemperature.hpp" -#include +#include #include #include diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 16c2e4767..866e21e46 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -8,7 +8,7 @@ #include -#include "../environment/global/SimTime.h" +#include "../environment/global/simulation_time.hpp" #include "../simulation/spacecraft/structure/structure.hpp" #include "simple_disturbance.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/environment/global/CMakeLists.txt b/src/environment/global/CMakeLists.txt index 286fdb983..c6bcdb459 100644 --- a/src/environment/global/CMakeLists.txt +++ b/src/environment/global/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC celestial_information.cpp hipparcos_catalogue.cpp gnss_satellites.cpp - SimTime.cpp + simulation_time.cpp clock_generator.cpp celestial_rotation.cpp initialize_global_environment.cpp diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 603f4f2ce..6254eec60 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -10,7 +10,7 @@ #include -#include "SimTime.h" +#include "simulation_time.hpp" /** * @class ClockGenerator diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index dbac82b4c..dbc067e9c 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -12,7 +12,7 @@ #include "gnss_satellites.hpp" #include "hipparcos_catalogue.hpp" -#include "SimTime.h" +#include "simulation_time.hpp" #include "celestial_information.hpp" /** diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index c1f96bc75..f24a1169e 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -16,7 +16,7 @@ #include #include -#include "SimTime.h" +#include "simulation_time.hpp" extern const double nan99; //!< Not at Number TODO: Should be moved to another place diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 5fbb22235..d554d1b36 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include diff --git a/src/environment/global/initialize_global_environment.hpp b/src/environment/global/initialize_global_environment.hpp index 0ac21d5a0..fc1619577 100644 --- a/src/environment/global/initialize_global_environment.hpp +++ b/src/environment/global/initialize_global_environment.hpp @@ -6,10 +6,9 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ -#include - #include #include +#include /** *@fn InitSimTime diff --git a/src/environment/global/SimTime.cpp b/src/environment/global/simulation_time.cpp similarity index 99% rename from src/environment/global/SimTime.cpp rename to src/environment/global/simulation_time.cpp index 95ce8b10e..e40c55662 100644 --- a/src/environment/global/SimTime.cpp +++ b/src/environment/global/simulation_time.cpp @@ -1,10 +1,10 @@ /** - *@file SimTime.cpp + *@file simulation_time.cpp *@brief Class to manage simulation time related information */ #define _CRT_SECURE_NO_WARNINGS -#include "SimTime.h" +#include "simulation_time.hpp" #include #include diff --git a/src/environment/global/SimTime.h b/src/environment/global/simulation_time.hpp similarity index 98% rename from src/environment/global/SimTime.h rename to src/environment/global/simulation_time.hpp index 4e8de7451..9ef27fe74 100644 --- a/src/environment/global/SimTime.h +++ b/src/environment/global/simulation_time.hpp @@ -1,10 +1,10 @@ /** - *@file SimTime.h + *@file simulation_time.hpp *@brief Class to manage simulation time related information */ -#ifndef __SIMULATION_TIME_H__ -#define __SIMULATION_TIME_H__ +#ifndef S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ +#define S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ #ifdef WIN32 #define _WINSOCKAPI_ // stops windows.h including winsock.h @@ -320,4 +320,4 @@ class SimTime : public ILoggable { */ void ConvJDtoCalndarDay(const double JD); }; -#endif //__SIMULATION_TIME_H__ +#endif // S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ From 4ec94074b7e82a9011e10ed13c564818010138cb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:46:40 +0100 Subject: [PATCH 0227/1086] Rename Atmosphere --- src/disturbances/air_drag.hpp | 2 +- src/environment/local/CMakeLists.txt | 2 +- src/environment/local/InitLocalEnvironment.hpp | 2 +- src/environment/local/LocalEnvironment.h | 2 +- src/environment/local/{Atmosphere.cpp => atmosphere.cpp} | 4 ++-- src/environment/local/{Atmosphere.h => atmosphere.hpp} | 8 ++++---- 6 files changed, 10 insertions(+), 10 deletions(-) rename src/environment/local/{Atmosphere.cpp => atmosphere.cpp} (99%) rename src/environment/local/{Atmosphere.h => atmosphere.hpp} (95%) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index a5c9793d3..bb334c468 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../environment/local/Atmosphere.h" +#include "../environment/local/atmosphere.hpp" #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index 308fa894b..4d52ff3bd 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -2,7 +2,7 @@ project(LOCAL_ENVIRONMENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Atmosphere.cpp + atmosphere.cpp LocalEnvironment.cpp MagEnvironment.cpp SRPEnvironment.cpp diff --git a/src/environment/local/InitLocalEnvironment.hpp b/src/environment/local/InitLocalEnvironment.hpp index 90e06edd4..4ff76d68d 100644 --- a/src/environment/local/InitLocalEnvironment.hpp +++ b/src/environment/local/InitLocalEnvironment.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/environment/local/LocalEnvironment.h b/src/environment/local/LocalEnvironment.h index 7638d91ae..8612290de 100644 --- a/src/environment/local/LocalEnvironment.h +++ b/src/environment/local/LocalEnvironment.h @@ -7,7 +7,7 @@ #include #include -#include "Atmosphere.h" +#include "atmosphere.hpp" #include "LocalCelestialInformation.h" #include "MagEnvironment.h" #include "SRPEnvironment.h" diff --git a/src/environment/local/Atmosphere.cpp b/src/environment/local/atmosphere.cpp similarity index 99% rename from src/environment/local/Atmosphere.cpp rename to src/environment/local/atmosphere.cpp index 034ee21da..e90ce32bc 100644 --- a/src/environment/local/Atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -1,9 +1,9 @@ /** - * @file Atmosphere.cpp + * @file atmosphere.cpp * @brief Class to calculate earth's atmospheric density */ -#include "Atmosphere.h" +#include "atmosphere.hpp" #include #include diff --git a/src/environment/local/Atmosphere.h b/src/environment/local/atmosphere.hpp similarity index 95% rename from src/environment/local/Atmosphere.h rename to src/environment/local/atmosphere.hpp index 68f535199..52d9de7f7 100644 --- a/src/environment/local/Atmosphere.h +++ b/src/environment/local/atmosphere.hpp @@ -1,11 +1,11 @@ /** - * @file Atmosphere.h + * @file atmosphere.hpp * @brief Class to calculate earth's atmospheric density */ #pragma once -#ifndef __Atmosphere_H__ -#define __Atmosphere_H__ +#ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ +#define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #include #include @@ -113,4 +113,4 @@ class Atmosphere : public ILoggable { double AddNoise(double rho); }; -#endif //__Atmosphere.h__ +#endif // S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ From 13b70cf1241ca9f5c42bc55ae3b7926d050809ed Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:50:43 +0100 Subject: [PATCH 0228/1086] Rename InitLocalEnvironment --- src/environment/local/CMakeLists.txt | 2 +- src/environment/local/LocalEnvironment.cpp | 2 +- ...vironment.cpp => initialize_local_environment.cpp} | 4 ++-- ...vironment.hpp => initialize_local_environment.hpp} | 11 ++++++++--- 4 files changed, 12 insertions(+), 7 deletions(-) rename src/environment/local/{InitLocalEnvironment.cpp => initialize_local_environment.cpp} (97%) rename src/environment/local/{InitLocalEnvironment.hpp => initialize_local_environment.hpp} (78%) diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index 4d52ff3bd..e5bc329dd 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -7,7 +7,7 @@ add_library(${PROJECT_NAME} STATIC MagEnvironment.cpp SRPEnvironment.cpp LocalCelestialInformation.cpp - InitLocalEnvironment.cpp + initialize_local_environment.cpp ) include(../../../common.cmake) diff --git a/src/environment/local/LocalEnvironment.cpp b/src/environment/local/LocalEnvironment.cpp index 785d1255d..2901f5dbb 100644 --- a/src/environment/local/LocalEnvironment.cpp +++ b/src/environment/local/LocalEnvironment.cpp @@ -8,7 +8,7 @@ #include #include -#include "InitLocalEnvironment.hpp" +#include "initialize_local_environment.hpp" LocalEnvironment::LocalEnvironment(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { Initialize(sim_config, glo_env, sat_id); diff --git a/src/environment/local/InitLocalEnvironment.cpp b/src/environment/local/initialize_local_environment.cpp similarity index 97% rename from src/environment/local/InitLocalEnvironment.cpp rename to src/environment/local/initialize_local_environment.cpp index 7a1657271..841f895c7 100644 --- a/src/environment/local/InitLocalEnvironment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -1,9 +1,9 @@ /** - * @file InitLocalEnvironment.cpp + * @file initialize_local_environment.cpp * @brief Initialize functions for local environment classes */ -#include "InitLocalEnvironment.hpp" +#include "initialize_local_environment.hpp" #include diff --git a/src/environment/local/InitLocalEnvironment.hpp b/src/environment/local/initialize_local_environment.hpp similarity index 78% rename from src/environment/local/InitLocalEnvironment.hpp rename to src/environment/local/initialize_local_environment.hpp index 4ff76d68d..ddccdb8db 100644 --- a/src/environment/local/InitLocalEnvironment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -1,13 +1,16 @@ /** - * @file InitLocalEnvironment.h + * @file initialize_local_environment.hpp * @brief Initialize functions for local environment classes */ -#pragma once -#include +#ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ +#define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ + #include #include +#include + /** * @fn InitMagEnvironment * @brief Initialize magnetic field of the earth @@ -27,3 +30,5 @@ SRPEnvironment InitSRPEnvironment(std::string ini_path, LocalCelestialInformatio * @param [in] ini_path: Path to initialize file */ Atmosphere InitAtmosphere(std::string ini_path); + +#endif // S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ From b62788a5a3545f255da1f9686a292db97d6143f7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:53:05 +0100 Subject: [PATCH 0229/1086] Rename LocalCelestialInformation --- src/Component/AOCS/SunSensor.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/Component/Power/SAP.h | 2 +- src/Dynamics/Attitude/ControlledAttitude.h | 2 +- src/Dynamics/Dynamics.h | 2 +- src/environment/local/CMakeLists.txt | 2 +- src/environment/local/LocalEnvironment.h | 2 +- src/environment/local/SRPEnvironment.h | 2 +- ...ialInformation.cpp => local_celestial_information.cpp} | 4 ++-- ...stialInformation.h => local_celestial_information.hpp} | 8 ++++---- 10 files changed, 14 insertions(+), 14 deletions(-) rename src/environment/local/{LocalCelestialInformation.cpp => local_celestial_information.cpp} (98%) rename src/environment/local/{LocalCelestialInformation.h => local_celestial_information.hpp} (95%) diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index 14bae5d0a..d63b41c9b 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,7 +6,7 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index fb500210a..e848888f7 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -7,7 +7,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index e20e89bf5..2fe2bb07c 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Dynamics/Attitude/ControlledAttitude.h b/src/Dynamics/Attitude/ControlledAttitude.h index 48e06116c..e8011cd44 100644 --- a/src/Dynamics/Attitude/ControlledAttitude.h +++ b/src/Dynamics/Attitude/ControlledAttitude.h @@ -5,7 +5,7 @@ #ifndef __controlled_attitude_H__ #define __controlled_attitude_H__ -#include +#include #include diff --git a/src/Dynamics/Dynamics.h b/src/Dynamics/Dynamics.h index fb44400cf..818a56002 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/Dynamics/Dynamics.h @@ -16,7 +16,7 @@ using libra::Vector; #include #include "../environment/global/simulation_time.hpp" -#include "../environment/local/LocalCelestialInformation.h" +#include "../environment/local/local_celestial_information.hpp" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" #include "./Orbit/Orbit.h" diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index e5bc329dd..246738042 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC LocalEnvironment.cpp MagEnvironment.cpp SRPEnvironment.cpp - LocalCelestialInformation.cpp + local_celestial_information.cpp initialize_local_environment.cpp ) diff --git a/src/environment/local/LocalEnvironment.h b/src/environment/local/LocalEnvironment.h index 8612290de..9ff0bf0b9 100644 --- a/src/environment/local/LocalEnvironment.h +++ b/src/environment/local/LocalEnvironment.h @@ -8,7 +8,7 @@ #include #include "atmosphere.hpp" -#include "LocalCelestialInformation.h" +#include "local_celestial_information.hpp" #include "MagEnvironment.h" #include "SRPEnvironment.h" #include "simulation/simulation_configuration.hpp" diff --git a/src/environment/local/SRPEnvironment.h b/src/environment/local/SRPEnvironment.h index b8eb3c79b..eca24ba05 100644 --- a/src/environment/local/SRPEnvironment.h +++ b/src/environment/local/SRPEnvironment.h @@ -4,7 +4,7 @@ */ #ifndef __SRPEnvironment_h__ #define __SRPEnvironment_h__ -#include +#include #include #include diff --git a/src/environment/local/LocalCelestialInformation.cpp b/src/environment/local/local_celestial_information.cpp similarity index 98% rename from src/environment/local/LocalCelestialInformation.cpp rename to src/environment/local/local_celestial_information.cpp index 270f1b60a..375b0b928 100644 --- a/src/environment/local/LocalCelestialInformation.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -1,9 +1,9 @@ /** - * @file LocalCelestialInformation.cpp + * @file local_celestial_information.cpp * @brief Class to manage celestial body information in the spacecraft body frame */ -#include "LocalCelestialInformation.h" +#include "local_celestial_information.hpp" #include #include diff --git a/src/environment/local/LocalCelestialInformation.h b/src/environment/local/local_celestial_information.hpp similarity index 95% rename from src/environment/local/LocalCelestialInformation.h rename to src/environment/local/local_celestial_information.hpp index 7d70fae68..899429ada 100644 --- a/src/environment/local/LocalCelestialInformation.h +++ b/src/environment/local/local_celestial_information.hpp @@ -1,10 +1,10 @@ /** - * @file LocalCelestialInformation.h + * @file local_celestial_information.hpp * @brief Class to manage celestial body information in the spacecraft body frame */ -#ifndef __local_celestial_information_H__ -#define __local_celestial_information_H__ +#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ +#define S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ #include "../global/celestial_information.hpp" @@ -117,4 +117,4 @@ void Convert_i2b(const double* src_i, double* dst_b, const Quaternion q_i2b); */ void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const Quaternion q_i2b, const Vector<3> bodyrate_b); -#endif //__local_celestial_information_H__ +#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ From 526517ac960dad9cbcf94ce26ae60a301ad70d07 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:55:29 +0100 Subject: [PATCH 0230/1086] Rename LocalEnvironment --- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/STT.h | 2 +- src/disturbances/acceleration_disturbance.hpp | 2 +- src/disturbances/simple_disturbance.hpp | 2 +- src/environment/local/CMakeLists.txt | 2 +- .../{LocalEnvironment.cpp => local_environment.cpp} | 4 ++-- .../{LocalEnvironment.h => local_environment.hpp} | 13 +++++++++---- src/simulation/spacecraft/spacecraft.hpp | 2 +- 9 files changed, 18 insertions(+), 13 deletions(-) rename src/environment/local/{LocalEnvironment.cpp => local_environment.cpp} (97%) rename src/environment/local/{LocalEnvironment.h => local_environment.hpp} (92%) diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index d3b3ad7b2..36932a1c2 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,7 +6,7 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index a4c8a1f24..3575c56dc 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,7 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index 41d47fd02..340166368 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -9,7 +9,7 @@ #define __STT_H__ #include -#include +#include #include #include diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index fac2b33db..3a4f9e75b 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -7,7 +7,7 @@ #define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ #include "../Dynamics/Dynamics.h" -#include "../environment/local/LocalEnvironment.h" +#include "../environment/local/local_environment.hpp" #include "disturbance.hpp" /** diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index d191d66c7..a4fb9c4fb 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -9,7 +9,7 @@ #define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ #include "../Dynamics/Dynamics.h" -#include "../environment/local/LocalEnvironment.h" +#include "../environment/local/local_environment.hpp" #include "disturbance.hpp" /** diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index 246738042..e871d5d0c 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC atmosphere.cpp - LocalEnvironment.cpp + local_environment.cpp MagEnvironment.cpp SRPEnvironment.cpp local_celestial_information.cpp diff --git a/src/environment/local/LocalEnvironment.cpp b/src/environment/local/local_environment.cpp similarity index 97% rename from src/environment/local/LocalEnvironment.cpp rename to src/environment/local/local_environment.cpp index 2901f5dbb..7cb346fc2 100644 --- a/src/environment/local/LocalEnvironment.cpp +++ b/src/environment/local/local_environment.cpp @@ -1,8 +1,8 @@ /** - * @file LocalEnvironment.cpp + * @file local_environment.cpp * @brief Class to manage local environments */ -#include "LocalEnvironment.h" +#include "local_environment.hpp" #include #include diff --git a/src/environment/local/LocalEnvironment.h b/src/environment/local/local_environment.hpp similarity index 92% rename from src/environment/local/LocalEnvironment.h rename to src/environment/local/local_environment.hpp index 9ff0bf0b9..a16a9c2c5 100644 --- a/src/environment/local/LocalEnvironment.h +++ b/src/environment/local/local_environment.hpp @@ -1,16 +1,19 @@ /** - * @file LocalEnvironment.h + * @file local_environment.hpp * @brief Class to manage local environments */ -#pragma once + +#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ +#define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ #include + #include -#include "atmosphere.hpp" -#include "local_celestial_information.hpp" #include "MagEnvironment.h" #include "SRPEnvironment.h" +#include "atmosphere.hpp" +#include "local_celestial_information.hpp" #include "simulation/simulation_configuration.hpp" class Logger; @@ -85,3 +88,5 @@ class LocalEnvironment { SRPEnvironment* srp_; //!< Solar radiation pressure LocalCelestialInformation* celes_info_; //!< Celestial information }; + +#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 27d43dd79..95e666a23 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include From d502cc84d03f3a07afd7fb83e3773f6bfe60be45 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 14:57:57 +0100 Subject: [PATCH 0231/1086] Rename MagEnvironment --- src/environment/local/CMakeLists.txt | 2 +- .../local/{MagEnvironment.cpp => geomagnetic_field.cpp} | 4 ++-- .../local/{MagEnvironment.h => geomagnetic_field.hpp} | 9 +++++---- src/environment/local/initialize_local_environment.hpp | 2 +- src/environment/local/local_environment.hpp | 2 +- 5 files changed, 10 insertions(+), 9 deletions(-) rename src/environment/local/{MagEnvironment.cpp => geomagnetic_field.cpp} (96%) rename src/environment/local/{MagEnvironment.h => geomagnetic_field.hpp} (93%) diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index e871d5d0c..513db4c88 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC atmosphere.cpp local_environment.cpp - MagEnvironment.cpp + geomagnetic_field.cpp SRPEnvironment.cpp local_celestial_information.cpp initialize_local_environment.cpp diff --git a/src/environment/local/MagEnvironment.cpp b/src/environment/local/geomagnetic_field.cpp similarity index 96% rename from src/environment/local/MagEnvironment.cpp rename to src/environment/local/geomagnetic_field.cpp index 30fa63d3c..59dad1928 100644 --- a/src/environment/local/MagEnvironment.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -1,9 +1,9 @@ /** - * @file MagEnvironment.cpp + * @file geomagnetic_field.cpp * @brief Class to calculate magnetic field of the earth */ -#include "MagEnvironment.h" +#include "geomagnetic_field.hpp" #include #include diff --git a/src/environment/local/MagEnvironment.h b/src/environment/local/geomagnetic_field.hpp similarity index 93% rename from src/environment/local/MagEnvironment.h rename to src/environment/local/geomagnetic_field.hpp index bb1e2702d..ccadd183e 100644 --- a/src/environment/local/MagEnvironment.h +++ b/src/environment/local/geomagnetic_field.hpp @@ -1,9 +1,10 @@ /** - * @file MagEnvironment.h + * @file geomagnetic_field.hpp * @brief Class to calculate magnetic field of the earth */ -#ifndef __MagEnvironment_H__ -#define __MagEnvironment_H__ + +#ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ +#define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ #include using libra::Vector; @@ -84,4 +85,4 @@ class MagEnvironment : public ILoggable { void AddNoise(double* mag_i_array); }; -#endif //__MagEnvironment_H__ +#endif // S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index ddccdb8db..2f4454b41 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index a16a9c2c5..a8f667342 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -10,7 +10,7 @@ #include -#include "MagEnvironment.h" +#include "geomagnetic_field.hpp" #include "SRPEnvironment.h" #include "atmosphere.hpp" #include "local_celestial_information.hpp" From 047684ee41b0aa07d712b0668e79a86f1c1107cf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 15:00:19 +0100 Subject: [PATCH 0232/1086] Rename SRPEnvironment --- src/Component/AOCS/SunSensor.h | 2 +- src/Component/Power/SAP.h | 2 +- src/environment/local/CMakeLists.txt | 2 +- .../local/initialize_local_environment.hpp | 2 +- src/environment/local/local_environment.hpp | 2 +- ....cpp => solar_radiation_pressure_environment.cpp} | 4 ++-- ...nt.h => solar_radiation_pressure_environment.hpp} | 12 +++++++----- 7 files changed, 14 insertions(+), 12 deletions(-) rename src/environment/local/{SRPEnvironment.cpp => solar_radiation_pressure_environment.cpp} (97%) rename src/environment/local/{SRPEnvironment.h => solar_radiation_pressure_environment.hpp} (91%) diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index d63b41c9b..ddbd13a70 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -7,7 +7,7 @@ #define __SunSensor_H__ #include -#include +#include #include #include diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index 2fe2bb07c..d2fac145f 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/environment/local/CMakeLists.txt b/src/environment/local/CMakeLists.txt index 513db4c88..12ae7d52d 100644 --- a/src/environment/local/CMakeLists.txt +++ b/src/environment/local/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC atmosphere.cpp local_environment.cpp geomagnetic_field.cpp - SRPEnvironment.cpp + solar_radiation_pressure_environment.cpp local_celestial_information.cpp initialize_local_environment.cpp ) diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index 2f4454b41..8adcdb920 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -7,7 +7,7 @@ #define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ #include -#include +#include #include diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index a8f667342..10e1f8980 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -11,7 +11,7 @@ #include #include "geomagnetic_field.hpp" -#include "SRPEnvironment.h" +#include "solar_radiation_pressure_environment.hpp" #include "atmosphere.hpp" #include "local_celestial_information.hpp" #include "simulation/simulation_configuration.hpp" diff --git a/src/environment/local/SRPEnvironment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp similarity index 97% rename from src/environment/local/SRPEnvironment.cpp rename to src/environment/local/solar_radiation_pressure_environment.cpp index e75ce790c..b3c4a9003 100644 --- a/src/environment/local/SRPEnvironment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -1,8 +1,8 @@ /** - * @file SRPEnvironment.cpp + * @file solar_radiation_pressure_environment.cpp * @brief Class to calculate Solar Radiation Pressure */ -#include "SRPEnvironment.h" +#include "solar_radiation_pressure_environment.hpp" #include diff --git a/src/environment/local/SRPEnvironment.h b/src/environment/local/solar_radiation_pressure_environment.hpp similarity index 91% rename from src/environment/local/SRPEnvironment.h rename to src/environment/local/solar_radiation_pressure_environment.hpp index eca24ba05..841e9ebbe 100644 --- a/src/environment/local/SRPEnvironment.h +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -1,13 +1,15 @@ /** - * @file SRPEnvironment.h + * @file solar_radiation_pressure_environment.hpp * @brief Class to calculate Solar Radiation Pressure */ -#ifndef __SRPEnvironment_h__ -#define __SRPEnvironment_h__ -#include + +#ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ +#define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ + #include #include +#include using libra::Vector; @@ -102,4 +104,4 @@ class SRPEnvironment : public ILoggable { void CalcShadowCoefficient(std::string shadow_source_name); }; -#endif /* SRPEnvironment_h */ +#endif // S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ From fe8a1b5f073c422506035d7082569235d418f60a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 15:45:55 +0100 Subject: [PATCH 0233/1086] Fix format --- src/Component/AOCS/GNSSReceiver.h | 4 ++-- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/STT.cpp | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/CommGS/GScalculator.cpp | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 4 ++-- src/disturbances/air_drag.cpp | 2 +- src/disturbances/disturbances.cpp | 4 ++-- src/disturbances/disturbances.hpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/initialize_disturbances.hpp | 5 ++--- src/simulation/case/simulation_case.hpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- src/simulation/ground_station/ground_station.hpp | 3 +-- .../sample_ground_station/sample_ground_station.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 3 +-- src/simulation/spacecraft/spacecraft.hpp | 4 ++-- 21 files changed, 26 insertions(+), 29 deletions(-) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 8c497d63d..4b38b5f34 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -6,12 +6,12 @@ #pragma once #include -#include -#include #include #include #include +#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index 36932a1c2..89842e7ac 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,10 +6,10 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include #include #include +#include #include "../Abstract/ComponentBase.h" #include "../Abstract/SensorBase.h" diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index 3575c56dc..9cf7de1b6 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,6 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include #include #include @@ -14,6 +13,7 @@ #include #include #include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index 5599c0058..76f8a1d4e 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -8,9 +8,9 @@ #include #include -#include #include #include +#include #include using namespace std; diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index 340166368..fd29a2994 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -9,13 +9,13 @@ #define __STT_H__ #include -#include #include #include #include #include #include +#include #include #include "../Abstract/ComponentBase.h" diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 42a612808..96fd99fe3 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,10 +4,10 @@ */ #pragma once -#include #include #include +#include #include "ITickable.h" diff --git a/src/Component/CommGS/GScalculator.cpp b/src/Component/CommGS/GScalculator.cpp index 85b9438b7..7faa095a0 100644 --- a/src/Component/CommGS/GScalculator.cpp +++ b/src/Component/CommGS/GScalculator.cpp @@ -5,8 +5,8 @@ #include "GScalculator.h" -#include #include +#include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, const double EbN0, const double hardware_deterioration, const double coding_gain, const double margin_req, diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index ecaf55a5d..9f229e345 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,13 +6,13 @@ #pragma once #include -#include #include #include #include #include #include +#include #include using libra::Matrix; diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index e848888f7..94a1b0600 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -6,12 +6,12 @@ #pragma once #include #include -#include -#include #include #include #include +#include +#include #include /* diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index c0799da6a..ed93060e4 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,9 +5,9 @@ #include "air_drag.hpp" -#include #include #include +#include #include #include "../Interface/LogOutput/LogUtility.h" diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index f2e82be35..14077bdd9 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -7,13 +7,13 @@ #include -#include "solar_radiation_pressure_disturbance.hpp" -#include "third_body_gravity.hpp" #include "air_drag.hpp" #include "geopotential.hpp" #include "gravity_gradient.hpp" #include "initialize_disturbances.hpp" #include "magnetic_disturbance.hpp" +#include "solar_radiation_pressure_disturbance.hpp" +#include "third_body_gravity.hpp" Disturbances::Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { InitializeInstances(sim_config, sat_id, structure, glo_env); diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 866e21e46..1deaf2cbd 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -10,8 +10,8 @@ #include "../environment/global/simulation_time.hpp" #include "../simulation/spacecraft/structure/structure.hpp" -#include "simple_disturbance.hpp" #include "acceleration_disturbance.hpp" +#include "simple_disturbance.hpp" class Logger; diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index e04e25f36..5ee48c094 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -5,9 +5,9 @@ #include "geopotential.hpp" -#include #include #include +#include #include #include diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index c34bca564..ef58c658d 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -5,8 +5,8 @@ #include "gravity_gradient.hpp" -#include #include +#include #include #include diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index c05f3e857..b85ea823f 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -6,13 +6,12 @@ #ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ #define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ -#include -#include - #include #include #include #include +#include +#include /** * @fn InitAirDrag diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index ec0af7811..d097402e6 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include #include +#include #include #include "../simulation_configuration.hpp" diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index aca879271..9c3d9430d 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -9,9 +9,9 @@ #include #include -#include #include #include +#include #include GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id) { diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index eb53961c6..7fa8c3cf4 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,10 +6,9 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include - #include #include +#include #include #include "../simulation_configuration.hpp" diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 2f760f5d2..acaae191c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -8,9 +8,9 @@ #include #include -#include #include +#include #include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "../ground_station.hpp" diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 24dcbfbfb..aba4fb30f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,9 +5,8 @@ #include "sample_spacecraft.hpp" -#include - #include +#include #include "sample_components.hpp" diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 95e666a23..36ed73150 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -7,10 +7,10 @@ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #include -#include -#include #include +#include +#include #include #include "installed_components.hpp" From 95b5e36114f85fc066ede749a4707d9638b488a0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 15:57:29 +0100 Subject: [PATCH 0234/1086] Fix format --- src/Component/AOCS/SunSensor.h | 4 ++-- src/Component/Power/PCU_InitialStudy.cpp | 2 +- src/Component/Power/SAP.cpp | 1 + src/Component/Power/SAP.h | 4 ++-- src/Dynamics/Attitude/ControlledAttitude.h | 1 - src/Dynamics/Orbit/Orbit.h | 4 ++-- src/Dynamics/Orbit/Rk4OrbitPropagation.h | 3 +-- src/Dynamics/Orbit/Sgp4OrbitPropagation.h | 3 ++- src/Dynamics/Thermal/InitTemperature.cpp | 2 +- src/Dynamics/Thermal/Node.cpp | 2 +- src/Library/Geodesy/GeodeticPosition.cpp | 2 +- src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/environment/global/initialize_global_environment.cpp | 2 +- src/environment/local/initialize_local_environment.hpp | 3 +-- src/environment/local/local_environment.hpp | 4 ++-- .../local/solar_radiation_pressure_environment.cpp | 2 +- 18 files changed, 22 insertions(+), 23 deletions(-) diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index ddbd13a70..5eb9cca3d 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,13 +6,13 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include -#include #include #include #include #include +#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Component/Power/PCU_InitialStudy.cpp b/src/Component/Power/PCU_InitialStudy.cpp index a4f73151c..bca9c9529 100644 --- a/src/Component/Power/PCU_InitialStudy.cpp +++ b/src/Component/Power/PCU_InitialStudy.cpp @@ -6,9 +6,9 @@ #include "PCU_InitialStudy.h" #include -#include #include +#include PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time) : ComponentBase(prescaler, clock_gen), diff --git a/src/Component/Power/SAP.cpp b/src/Component/Power/SAP.cpp index 0a78b7aea..313ee8661 100644 --- a/src/Component/Power/SAP.cpp +++ b/src/Component/Power/SAP.cpp @@ -1,6 +1,7 @@ #include "SAP.h" #include + #include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index d2fac145f..e739ceed4 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,11 +4,11 @@ */ #pragma once -#include -#include #include #include +#include +#include #include "../Abstract/ComponentBase.h" diff --git a/src/Dynamics/Attitude/ControlledAttitude.h b/src/Dynamics/Attitude/ControlledAttitude.h index e8011cd44..7870d85d3 100644 --- a/src/Dynamics/Attitude/ControlledAttitude.h +++ b/src/Dynamics/Attitude/ControlledAttitude.h @@ -6,7 +6,6 @@ #define __controlled_attitude_H__ #include - #include #include "../Orbit/Orbit.h" diff --git a/src/Dynamics/Orbit/Orbit.h b/src/Dynamics/Orbit/Orbit.h index 9ff571bb7..6ec82c2f1 100644 --- a/src/Dynamics/Orbit/Orbit.h +++ b/src/Dynamics/Orbit/Orbit.h @@ -15,11 +15,11 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include #include -#include #include +#include +#include /** * @enum OrbitPropagateMode diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.h b/src/Dynamics/Orbit/Rk4OrbitPropagation.h index 76d14429b..c35121aa0 100644 --- a/src/Dynamics/Orbit/Rk4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Rk4OrbitPropagation.h @@ -2,9 +2,8 @@ * @file Rk4OrbitPropagation.h * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -#include - #include +#include #include "Orbit.h" diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h index ca67a50ed..22b2c45ec 100644 --- a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h +++ b/src/Dynamics/Orbit/Sgp4OrbitPropagation.h @@ -3,10 +3,11 @@ * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ #pragma once -#include #include #include +#include + #include "Orbit.h" /** diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/Dynamics/Thermal/InitTemperature.cpp index bd58876e7..439e182e2 100644 --- a/src/Dynamics/Thermal/InitTemperature.cpp +++ b/src/Dynamics/Thermal/InitTemperature.cpp @@ -1,8 +1,8 @@ #include "InitTemperature.hpp" -#include #include +#include #include #include "InitNode.hpp" diff --git a/src/Dynamics/Thermal/Node.cpp b/src/Dynamics/Thermal/Node.cpp index cade38606..daf67c3f0 100644 --- a/src/Dynamics/Thermal/Node.cpp +++ b/src/Dynamics/Thermal/Node.cpp @@ -1,7 +1,7 @@ #include "Node.h" -#include #include +#include using namespace std; using namespace libra; diff --git a/src/Library/Geodesy/GeodeticPosition.cpp b/src/Library/Geodesy/GeodeticPosition.cpp index 8c59f6c93..eef4c08fe 100644 --- a/src/Library/Geodesy/GeodeticPosition.cpp +++ b/src/Library/Geodesy/GeodeticPosition.cpp @@ -6,9 +6,9 @@ #include // TODO: do not to use the functions in SGP4 library -#include #include #include +#include GeodeticPosition::GeodeticPosition() { latitude_rad_ = 0.0; diff --git a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp index 779c7cd03..111a5ca7c 100644 --- a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp +++ b/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp @@ -12,11 +12,11 @@ extern "C" { } #include /* for malloc/free */ -#include #include #include #include #include /* maths functions */ +#include #include #include "Wrapper_nrlmsise00.h" /* header for nrlmsise-00.h */ diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index bb334c468..998fb1039 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,10 +9,10 @@ #include #include -#include "../environment/local/atmosphere.hpp" #include "../Interface/LogOutput/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" +#include "../environment/local/atmosphere.hpp" #include "surface_force.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index dbc067e9c..ff7eeaea8 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -10,10 +10,10 @@ #include +#include "celestial_information.hpp" #include "gnss_satellites.hpp" #include "hipparcos_catalogue.hpp" #include "simulation_time.hpp" -#include "celestial_information.hpp" /** * @class GlobalEnvironment diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index d554d1b36..529ac5ef0 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -6,9 +6,9 @@ #include #include -#include #include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index 8adcdb920..4d0098f96 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -6,11 +6,10 @@ #ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ +#include #include #include -#include - /** * @fn InitMagEnvironment * @brief Initialize magnetic field of the earth diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 10e1f8980..bf18e9129 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -10,11 +10,11 @@ #include -#include "geomagnetic_field.hpp" -#include "solar_radiation_pressure_environment.hpp" #include "atmosphere.hpp" +#include "geomagnetic_field.hpp" #include "local_celestial_information.hpp" #include "simulation/simulation_configuration.hpp" +#include "solar_radiation_pressure_environment.hpp" class Logger; class SimTime; diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index b3c4a9003..87f241039 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -6,11 +6,11 @@ #include -#include #include #include #include #include +#include #include using libra::Vector; From 53690a07328e8fa5307c6f23a134d28d4a1bbb4b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 15:09:42 +0100 Subject: [PATCH 0235/1086] Rename Dynamics directory --- CMakeLists.txt | 2 +- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Component/AOCS/Gyro.h | 2 +- src/Component/AOCS/STT.h | 4 ++-- src/Component/CommGS/GScalculator.h | 3 ++- src/Component/IdealComponents/ForceGenerator.hpp | 2 +- src/Component/IdealComponents/TorqueGenerator.hpp | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- src/disturbances/acceleration_disturbance.hpp | 2 +- src/disturbances/simple_disturbance.hpp | 2 +- src/{Dynamics => dynamics}/Attitude/Attitude.cpp | 0 src/{Dynamics => dynamics}/Attitude/Attitude.h | 0 src/{Dynamics => dynamics}/Attitude/AttitudeRK4.cpp | 0 src/{Dynamics => dynamics}/Attitude/AttitudeRK4.h | 0 .../Attitude/ControlledAttitude.cpp | 0 src/{Dynamics => dynamics}/Attitude/ControlledAttitude.h | 0 src/{Dynamics => dynamics}/Attitude/InitAttitude.cpp | 0 src/{Dynamics => dynamics}/Attitude/InitAttitude.hpp | 0 src/{Dynamics => dynamics}/CMakeLists.txt | 0 src/{Dynamics => dynamics}/Dynamics.cpp | 0 src/{Dynamics => dynamics}/Dynamics.h | 8 ++++---- .../Orbit/EnckeOrbitPropagation.cpp | 0 src/{Dynamics => dynamics}/Orbit/EnckeOrbitPropagation.h | 0 src/{Dynamics => dynamics}/Orbit/InitOrbit.cpp | 0 src/{Dynamics => dynamics}/Orbit/InitOrbit.hpp | 0 .../Orbit/KeplerOrbitPropagation.cpp | 0 src/{Dynamics => dynamics}/Orbit/KeplerOrbitPropagation.h | 0 src/{Dynamics => dynamics}/Orbit/Orbit.cpp | 0 src/{Dynamics => dynamics}/Orbit/Orbit.h | 0 src/{Dynamics => dynamics}/Orbit/RelativeOrbit.cpp | 0 src/{Dynamics => dynamics}/Orbit/RelativeOrbit.h | 0 src/{Dynamics => dynamics}/Orbit/Rk4OrbitPropagation.cpp | 0 src/{Dynamics => dynamics}/Orbit/Rk4OrbitPropagation.h | 0 src/{Dynamics => dynamics}/Orbit/Sgp4OrbitPropagation.cpp | 0 src/{Dynamics => dynamics}/Orbit/Sgp4OrbitPropagation.h | 0 src/{Dynamics => dynamics}/Thermal/InitNode.cpp | 0 src/{Dynamics => dynamics}/Thermal/InitNode.hpp | 0 src/{Dynamics => dynamics}/Thermal/InitTemperature.cpp | 0 src/{Dynamics => dynamics}/Thermal/InitTemperature.hpp | 0 src/{Dynamics => dynamics}/Thermal/Node.cpp | 0 src/{Dynamics => dynamics}/Thermal/Node.h | 0 src/{Dynamics => dynamics}/Thermal/Temperature.cpp | 0 src/{Dynamics => dynamics}/Thermal/Temperature.h | 0 src/environment/local/local_environment.cpp | 4 ++-- src/environment/local/local_environment.hpp | 2 +- src/relative_information/relative_information.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- 50 files changed, 24 insertions(+), 23 deletions(-) rename src/{Dynamics => dynamics}/Attitude/Attitude.cpp (100%) rename src/{Dynamics => dynamics}/Attitude/Attitude.h (100%) rename src/{Dynamics => dynamics}/Attitude/AttitudeRK4.cpp (100%) rename src/{Dynamics => dynamics}/Attitude/AttitudeRK4.h (100%) rename src/{Dynamics => dynamics}/Attitude/ControlledAttitude.cpp (100%) rename src/{Dynamics => dynamics}/Attitude/ControlledAttitude.h (100%) rename src/{Dynamics => dynamics}/Attitude/InitAttitude.cpp (100%) rename src/{Dynamics => dynamics}/Attitude/InitAttitude.hpp (100%) rename src/{Dynamics => dynamics}/CMakeLists.txt (100%) rename src/{Dynamics => dynamics}/Dynamics.cpp (100%) rename src/{Dynamics => dynamics}/Dynamics.h (96%) rename src/{Dynamics => dynamics}/Orbit/EnckeOrbitPropagation.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/EnckeOrbitPropagation.h (100%) rename src/{Dynamics => dynamics}/Orbit/InitOrbit.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/InitOrbit.hpp (100%) rename src/{Dynamics => dynamics}/Orbit/KeplerOrbitPropagation.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/KeplerOrbitPropagation.h (100%) rename src/{Dynamics => dynamics}/Orbit/Orbit.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/Orbit.h (100%) rename src/{Dynamics => dynamics}/Orbit/RelativeOrbit.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/RelativeOrbit.h (100%) rename src/{Dynamics => dynamics}/Orbit/Rk4OrbitPropagation.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/Rk4OrbitPropagation.h (100%) rename src/{Dynamics => dynamics}/Orbit/Sgp4OrbitPropagation.cpp (100%) rename src/{Dynamics => dynamics}/Orbit/Sgp4OrbitPropagation.h (100%) rename src/{Dynamics => dynamics}/Thermal/InitNode.cpp (100%) rename src/{Dynamics => dynamics}/Thermal/InitNode.hpp (100%) rename src/{Dynamics => dynamics}/Thermal/InitTemperature.cpp (100%) rename src/{Dynamics => dynamics}/Thermal/InitTemperature.hpp (100%) rename src/{Dynamics => dynamics}/Thermal/Node.cpp (100%) rename src/{Dynamics => dynamics}/Thermal/Node.h (100%) rename src/{Dynamics => dynamics}/Thermal/Temperature.cpp (100%) rename src/{Dynamics => dynamics}/Thermal/Temperature.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6c080935f..afc07a906 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -66,7 +66,7 @@ include_directories(${NRLMSISE00_DIR}/src) add_subdirectory(src/simulation) add_subdirectory(src/environment/global) add_subdirectory(src/environment/local) -add_subdirectory(src/Dynamics) +add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/Component) add_subdirectory(src/relative_information) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 4b38b5f34..93eec74e9 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -5,8 +5,8 @@ #pragma once -#include #include +#include #include #include diff --git a/src/Component/AOCS/Gyro.h b/src/Component/AOCS/Gyro.h index b0de08d2d..c051380b8 100644 --- a/src/Component/AOCS/Gyro.h +++ b/src/Component/AOCS/Gyro.h @@ -6,8 +6,8 @@ #ifndef Gyro_H_ #define Gyro_H_ -#include #include +#include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index fd29a2994..3459d7889 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -8,8 +8,8 @@ #ifndef __STT_H__ #define __STT_H__ -#include #include +#include #include #include @@ -19,7 +19,7 @@ #include #include "../Abstract/ComponentBase.h" -#include "Dynamics/Dynamics.h" +#include "dynamics/Dynamics.h" /* * @class STT diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 9f229e345..78a999ea4 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -5,8 +5,9 @@ */ #pragma once -#include + #include +#include #include #include diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/Component/IdealComponents/ForceGenerator.hpp index f104edbc8..b93447d60 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/Component/IdealComponents/ForceGenerator.hpp @@ -5,8 +5,8 @@ #pragma once #include -#include #include +#include #include #include diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/Component/IdealComponents/TorqueGenerator.hpp index 8b507fbc0..d987bddad 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/Component/IdealComponents/TorqueGenerator.hpp @@ -5,8 +5,8 @@ #pragma once #include -#include #include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index 94a1b0600..c5498af73 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -5,8 +5,8 @@ #pragma once #include -#include #include +#include #include #include diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index e66a4b712..806cbf587 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index 3a4f9e75b..e7a185d69 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ #define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ -#include "../Dynamics/Dynamics.h" +#include "../dynamics/Dynamics.h" #include "../environment/local/local_environment.hpp" #include "disturbance.hpp" diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index a4fb9c4fb..01c59f3b6 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -8,7 +8,7 @@ #ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ #define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ -#include "../Dynamics/Dynamics.h" +#include "../dynamics/Dynamics.h" #include "../environment/local/local_environment.hpp" #include "disturbance.hpp" diff --git a/src/Dynamics/Attitude/Attitude.cpp b/src/dynamics/Attitude/Attitude.cpp similarity index 100% rename from src/Dynamics/Attitude/Attitude.cpp rename to src/dynamics/Attitude/Attitude.cpp diff --git a/src/Dynamics/Attitude/Attitude.h b/src/dynamics/Attitude/Attitude.h similarity index 100% rename from src/Dynamics/Attitude/Attitude.h rename to src/dynamics/Attitude/Attitude.h diff --git a/src/Dynamics/Attitude/AttitudeRK4.cpp b/src/dynamics/Attitude/AttitudeRK4.cpp similarity index 100% rename from src/Dynamics/Attitude/AttitudeRK4.cpp rename to src/dynamics/Attitude/AttitudeRK4.cpp diff --git a/src/Dynamics/Attitude/AttitudeRK4.h b/src/dynamics/Attitude/AttitudeRK4.h similarity index 100% rename from src/Dynamics/Attitude/AttitudeRK4.h rename to src/dynamics/Attitude/AttitudeRK4.h diff --git a/src/Dynamics/Attitude/ControlledAttitude.cpp b/src/dynamics/Attitude/ControlledAttitude.cpp similarity index 100% rename from src/Dynamics/Attitude/ControlledAttitude.cpp rename to src/dynamics/Attitude/ControlledAttitude.cpp diff --git a/src/Dynamics/Attitude/ControlledAttitude.h b/src/dynamics/Attitude/ControlledAttitude.h similarity index 100% rename from src/Dynamics/Attitude/ControlledAttitude.h rename to src/dynamics/Attitude/ControlledAttitude.h diff --git a/src/Dynamics/Attitude/InitAttitude.cpp b/src/dynamics/Attitude/InitAttitude.cpp similarity index 100% rename from src/Dynamics/Attitude/InitAttitude.cpp rename to src/dynamics/Attitude/InitAttitude.cpp diff --git a/src/Dynamics/Attitude/InitAttitude.hpp b/src/dynamics/Attitude/InitAttitude.hpp similarity index 100% rename from src/Dynamics/Attitude/InitAttitude.hpp rename to src/dynamics/Attitude/InitAttitude.hpp diff --git a/src/Dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt similarity index 100% rename from src/Dynamics/CMakeLists.txt rename to src/dynamics/CMakeLists.txt diff --git a/src/Dynamics/Dynamics.cpp b/src/dynamics/Dynamics.cpp similarity index 100% rename from src/Dynamics/Dynamics.cpp rename to src/dynamics/Dynamics.cpp diff --git a/src/Dynamics/Dynamics.h b/src/dynamics/Dynamics.h similarity index 96% rename from src/Dynamics/Dynamics.h rename to src/dynamics/Dynamics.h index 818a56002..c3d160c9f 100644 --- a/src/Dynamics/Dynamics.h +++ b/src/dynamics/Dynamics.h @@ -10,10 +10,10 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include -#include -#include -#include +#include +#include +#include +#include #include "../environment/global/simulation_time.hpp" #include "../environment/local/local_celestial_information.hpp" diff --git a/src/Dynamics/Orbit/EnckeOrbitPropagation.cpp b/src/dynamics/Orbit/EnckeOrbitPropagation.cpp similarity index 100% rename from src/Dynamics/Orbit/EnckeOrbitPropagation.cpp rename to src/dynamics/Orbit/EnckeOrbitPropagation.cpp diff --git a/src/Dynamics/Orbit/EnckeOrbitPropagation.h b/src/dynamics/Orbit/EnckeOrbitPropagation.h similarity index 100% rename from src/Dynamics/Orbit/EnckeOrbitPropagation.h rename to src/dynamics/Orbit/EnckeOrbitPropagation.h diff --git a/src/Dynamics/Orbit/InitOrbit.cpp b/src/dynamics/Orbit/InitOrbit.cpp similarity index 100% rename from src/Dynamics/Orbit/InitOrbit.cpp rename to src/dynamics/Orbit/InitOrbit.cpp diff --git a/src/Dynamics/Orbit/InitOrbit.hpp b/src/dynamics/Orbit/InitOrbit.hpp similarity index 100% rename from src/Dynamics/Orbit/InitOrbit.hpp rename to src/dynamics/Orbit/InitOrbit.hpp diff --git a/src/Dynamics/Orbit/KeplerOrbitPropagation.cpp b/src/dynamics/Orbit/KeplerOrbitPropagation.cpp similarity index 100% rename from src/Dynamics/Orbit/KeplerOrbitPropagation.cpp rename to src/dynamics/Orbit/KeplerOrbitPropagation.cpp diff --git a/src/Dynamics/Orbit/KeplerOrbitPropagation.h b/src/dynamics/Orbit/KeplerOrbitPropagation.h similarity index 100% rename from src/Dynamics/Orbit/KeplerOrbitPropagation.h rename to src/dynamics/Orbit/KeplerOrbitPropagation.h diff --git a/src/Dynamics/Orbit/Orbit.cpp b/src/dynamics/Orbit/Orbit.cpp similarity index 100% rename from src/Dynamics/Orbit/Orbit.cpp rename to src/dynamics/Orbit/Orbit.cpp diff --git a/src/Dynamics/Orbit/Orbit.h b/src/dynamics/Orbit/Orbit.h similarity index 100% rename from src/Dynamics/Orbit/Orbit.h rename to src/dynamics/Orbit/Orbit.h diff --git a/src/Dynamics/Orbit/RelativeOrbit.cpp b/src/dynamics/Orbit/RelativeOrbit.cpp similarity index 100% rename from src/Dynamics/Orbit/RelativeOrbit.cpp rename to src/dynamics/Orbit/RelativeOrbit.cpp diff --git a/src/Dynamics/Orbit/RelativeOrbit.h b/src/dynamics/Orbit/RelativeOrbit.h similarity index 100% rename from src/Dynamics/Orbit/RelativeOrbit.h rename to src/dynamics/Orbit/RelativeOrbit.h diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.cpp b/src/dynamics/Orbit/Rk4OrbitPropagation.cpp similarity index 100% rename from src/Dynamics/Orbit/Rk4OrbitPropagation.cpp rename to src/dynamics/Orbit/Rk4OrbitPropagation.cpp diff --git a/src/Dynamics/Orbit/Rk4OrbitPropagation.h b/src/dynamics/Orbit/Rk4OrbitPropagation.h similarity index 100% rename from src/Dynamics/Orbit/Rk4OrbitPropagation.h rename to src/dynamics/Orbit/Rk4OrbitPropagation.h diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp b/src/dynamics/Orbit/Sgp4OrbitPropagation.cpp similarity index 100% rename from src/Dynamics/Orbit/Sgp4OrbitPropagation.cpp rename to src/dynamics/Orbit/Sgp4OrbitPropagation.cpp diff --git a/src/Dynamics/Orbit/Sgp4OrbitPropagation.h b/src/dynamics/Orbit/Sgp4OrbitPropagation.h similarity index 100% rename from src/Dynamics/Orbit/Sgp4OrbitPropagation.h rename to src/dynamics/Orbit/Sgp4OrbitPropagation.h diff --git a/src/Dynamics/Thermal/InitNode.cpp b/src/dynamics/Thermal/InitNode.cpp similarity index 100% rename from src/Dynamics/Thermal/InitNode.cpp rename to src/dynamics/Thermal/InitNode.cpp diff --git a/src/Dynamics/Thermal/InitNode.hpp b/src/dynamics/Thermal/InitNode.hpp similarity index 100% rename from src/Dynamics/Thermal/InitNode.hpp rename to src/dynamics/Thermal/InitNode.hpp diff --git a/src/Dynamics/Thermal/InitTemperature.cpp b/src/dynamics/Thermal/InitTemperature.cpp similarity index 100% rename from src/Dynamics/Thermal/InitTemperature.cpp rename to src/dynamics/Thermal/InitTemperature.cpp diff --git a/src/Dynamics/Thermal/InitTemperature.hpp b/src/dynamics/Thermal/InitTemperature.hpp similarity index 100% rename from src/Dynamics/Thermal/InitTemperature.hpp rename to src/dynamics/Thermal/InitTemperature.hpp diff --git a/src/Dynamics/Thermal/Node.cpp b/src/dynamics/Thermal/Node.cpp similarity index 100% rename from src/Dynamics/Thermal/Node.cpp rename to src/dynamics/Thermal/Node.cpp diff --git a/src/Dynamics/Thermal/Node.h b/src/dynamics/Thermal/Node.h similarity index 100% rename from src/Dynamics/Thermal/Node.h rename to src/dynamics/Thermal/Node.h diff --git a/src/Dynamics/Thermal/Temperature.cpp b/src/dynamics/Thermal/Temperature.cpp similarity index 100% rename from src/Dynamics/Thermal/Temperature.cpp rename to src/dynamics/Thermal/Temperature.cpp diff --git a/src/Dynamics/Thermal/Temperature.h b/src/dynamics/Thermal/Temperature.h similarity index 100% rename from src/Dynamics/Thermal/Temperature.h rename to src/dynamics/Thermal/Temperature.h diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 7cb346fc2..c6e5e6679 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,8 +4,8 @@ */ #include "local_environment.hpp" -#include -#include +#include +#include #include #include "initialize_local_environment.hpp" diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index bf18e9129..1c9340ade 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ -#include +#include #include diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 68cf555bb..98701d9bf 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -8,7 +8,7 @@ #include -#include "../Dynamics/Dynamics.h" +#include "../dynamics/Dynamics.h" #include "../Interface/LogOutput/ILoggable.h" #include "../Interface/LogOutput/Logger.h" diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index acaae191c..3a3af59b7 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 13696b310..865f52fce 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 36ed73150..e2a1a0363 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ -#include +#include #include #include From 52461edb59a59b70651bd9075332e2b68ec94cc2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 15:11:57 +0100 Subject: [PATCH 0236/1086] Rename Dynamics files --- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Component/AOCS/Gyro.h | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/IdealComponents/ForceGenerator.hpp | 2 +- src/Component/IdealComponents/TorqueGenerator.hpp | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- src/disturbances/acceleration_disturbance.hpp | 2 +- src/disturbances/simple_disturbance.hpp | 2 +- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/{Dynamics.cpp => dynamics.cpp} | 4 ++-- src/dynamics/{Dynamics.h => dynamics.hpp} | 8 ++++---- src/environment/local/local_environment.hpp | 2 +- src/relative_information/relative_information.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 3 +-- 17 files changed, 21 insertions(+), 22 deletions(-) rename src/dynamics/{Dynamics.cpp => dynamics.cpp} (98%) rename src/dynamics/{Dynamics.h => dynamics.hpp} (97%) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 93eec74e9..8042c96aa 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -6,10 +6,10 @@ #pragma once #include -#include #include #include +#include #include #include diff --git a/src/Component/AOCS/Gyro.h b/src/Component/AOCS/Gyro.h index c051380b8..1572a326e 100644 --- a/src/Component/AOCS/Gyro.h +++ b/src/Component/AOCS/Gyro.h @@ -7,9 +7,9 @@ #define Gyro_H_ #include -#include #include +#include #include "../Abstract/ComponentBase.h" #include "../Abstract/SensorBase.h" diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index 3459d7889..6c858bf0a 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -19,7 +19,7 @@ #include #include "../Abstract/ComponentBase.h" -#include "dynamics/Dynamics.h" +#include "dynamics/dynamics.hpp" /* * @class STT diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 78a999ea4..8110d0547 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -7,12 +7,12 @@ #pragma once #include -#include #include #include #include #include +#include #include #include diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/Component/IdealComponents/ForceGenerator.hpp index b93447d60..28537de49 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/Component/IdealComponents/ForceGenerator.hpp @@ -6,10 +6,10 @@ #include #include -#include #include #include +#include /* * @class ForceGenerator diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/Component/IdealComponents/TorqueGenerator.hpp index d987bddad..581a4d17f 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/Component/IdealComponents/TorqueGenerator.hpp @@ -6,10 +6,10 @@ #include #include -#include #include #include +#include /* * @class TorqueGenerator diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 806cbf587..6c19966c9 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index e7a185d69..c6be61ce4 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ #define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ -#include "../dynamics/Dynamics.h" +#include "../dynamics/dynamics.hpp" #include "../environment/local/local_environment.hpp" #include "disturbance.hpp" diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 01c59f3b6..4e72a5e43 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -8,7 +8,7 @@ #ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ #define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ -#include "../dynamics/Dynamics.h" +#include "../dynamics/dynamics.hpp" #include "../environment/local/local_environment.hpp" #include "disturbance.hpp" diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 4e8ed0f8d..91b282754 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -20,7 +20,7 @@ add_library(${PROJECT_NAME} STATIC Attitude/ControlledAttitude.cpp Attitude/InitAttitude.cpp - Dynamics.cpp + dynamics.cpp ) include(../../common.cmake) diff --git a/src/dynamics/Dynamics.cpp b/src/dynamics/dynamics.cpp similarity index 98% rename from src/dynamics/Dynamics.cpp rename to src/dynamics/dynamics.cpp index 4bb0e7724..daf7b91a0 100644 --- a/src/dynamics/Dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -1,9 +1,9 @@ /** - * @file Dynamics.cpp + * @file dynamics.cpp * @brief Class to manage dynamics of spacecraft */ -#include "Dynamics.h" +#include "dynamics.hpp" #include "../relative_information/relative_information.hpp" diff --git a/src/dynamics/Dynamics.h b/src/dynamics/dynamics.hpp similarity index 97% rename from src/dynamics/Dynamics.h rename to src/dynamics/dynamics.hpp index c3d160c9f..a0f7958b2 100644 --- a/src/dynamics/Dynamics.h +++ b/src/dynamics/dynamics.hpp @@ -1,9 +1,9 @@ /** - * @file Dynamics.h + * @file dynamics.hpp * @brief Class to manage dynamics of spacecraft */ -#ifndef __dynamics_H__ -#define __dynamics_H__ +#ifndef S2E_DYNAMICS_DYNAMICS_H_ +#define S2E_DYNAMICS_DYNAMICS_H_ #include @@ -138,4 +138,4 @@ class Dynamics { const Structure* structure_; //!< Structure information }; -#endif //__dynamics_H__ +#endif // S2E_DYNAMICS_DYNAMICS_H_ diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 1c9340ade..da46eb8bd 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ -#include +#include #include diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 98701d9bf..0a332a9a4 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -8,7 +8,7 @@ #include -#include "../dynamics/Dynamics.h" +#include "../dynamics/dynamics.hpp" #include "../Interface/LogOutput/ILoggable.h" #include "../Interface/LogOutput/Logger.h" diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 3a3af59b7..0db4f1006 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -7,9 +7,9 @@ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #include -#include #include +#include #include #include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 865f52fce..e224fdb68 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index e2a1a0363..5a3255995 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -6,9 +6,8 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ #define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ -#include - #include +#include #include #include #include From 8444428adc1b1ca64d1a43a271b58c372798a73b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:21:32 +0100 Subject: [PATCH 0237/1086] Rename Attitude, Orbit, and Thermal directory --- src/Component/AOCS/STT.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/dynamics/CMakeLists.txt | 30 +++++++++---------- .../{Attitude => attitude}/Attitude.cpp | 0 .../{Attitude => attitude}/Attitude.h | 0 .../{Attitude => attitude}/AttitudeRK4.cpp | 0 .../{Attitude => attitude}/AttitudeRK4.h | 0 .../ControlledAttitude.cpp | 0 .../ControlledAttitude.h | 2 +- .../{Attitude => attitude}/InitAttitude.cpp | 0 .../{Attitude => attitude}/InitAttitude.hpp | 0 src/dynamics/dynamics.hpp | 12 ++++---- .../EnckeOrbitPropagation.cpp | 0 .../{Orbit => orbit}/EnckeOrbitPropagation.h | 0 src/dynamics/{Orbit => orbit}/InitOrbit.cpp | 0 src/dynamics/{Orbit => orbit}/InitOrbit.hpp | 0 .../KeplerOrbitPropagation.cpp | 0 .../{Orbit => orbit}/KeplerOrbitPropagation.h | 0 src/dynamics/{Orbit => orbit}/Orbit.cpp | 0 src/dynamics/{Orbit => orbit}/Orbit.h | 0 .../{Orbit => orbit}/RelativeOrbit.cpp | 0 src/dynamics/{Orbit => orbit}/RelativeOrbit.h | 0 .../{Orbit => orbit}/Rk4OrbitPropagation.cpp | 0 .../{Orbit => orbit}/Rk4OrbitPropagation.h | 0 .../{Orbit => orbit}/Sgp4OrbitPropagation.cpp | 0 .../{Orbit => orbit}/Sgp4OrbitPropagation.h | 0 .../{Thermal => thermal}/InitNode.cpp | 0 .../{Thermal => thermal}/InitNode.hpp | 0 .../{Thermal => thermal}/InitTemperature.cpp | 0 .../{Thermal => thermal}/InitTemperature.hpp | 0 src/dynamics/{Thermal => thermal}/Node.cpp | 0 src/dynamics/{Thermal => thermal}/Node.h | 0 .../{Thermal => thermal}/Temperature.cpp | 0 .../{Thermal => thermal}/Temperature.h | 0 src/environment/local/local_environment.cpp | 4 +-- 35 files changed, 26 insertions(+), 26 deletions(-) rename src/dynamics/{Attitude => attitude}/Attitude.cpp (100%) rename src/dynamics/{Attitude => attitude}/Attitude.h (100%) rename src/dynamics/{Attitude => attitude}/AttitudeRK4.cpp (100%) rename src/dynamics/{Attitude => attitude}/AttitudeRK4.h (100%) rename src/dynamics/{Attitude => attitude}/ControlledAttitude.cpp (100%) rename src/dynamics/{Attitude => attitude}/ControlledAttitude.h (99%) rename src/dynamics/{Attitude => attitude}/InitAttitude.cpp (100%) rename src/dynamics/{Attitude => attitude}/InitAttitude.hpp (100%) rename src/dynamics/{Orbit => orbit}/EnckeOrbitPropagation.cpp (100%) rename src/dynamics/{Orbit => orbit}/EnckeOrbitPropagation.h (100%) rename src/dynamics/{Orbit => orbit}/InitOrbit.cpp (100%) rename src/dynamics/{Orbit => orbit}/InitOrbit.hpp (100%) rename src/dynamics/{Orbit => orbit}/KeplerOrbitPropagation.cpp (100%) rename src/dynamics/{Orbit => orbit}/KeplerOrbitPropagation.h (100%) rename src/dynamics/{Orbit => orbit}/Orbit.cpp (100%) rename src/dynamics/{Orbit => orbit}/Orbit.h (100%) rename src/dynamics/{Orbit => orbit}/RelativeOrbit.cpp (100%) rename src/dynamics/{Orbit => orbit}/RelativeOrbit.h (100%) rename src/dynamics/{Orbit => orbit}/Rk4OrbitPropagation.cpp (100%) rename src/dynamics/{Orbit => orbit}/Rk4OrbitPropagation.h (100%) rename src/dynamics/{Orbit => orbit}/Sgp4OrbitPropagation.cpp (100%) rename src/dynamics/{Orbit => orbit}/Sgp4OrbitPropagation.h (100%) rename src/dynamics/{Thermal => thermal}/InitNode.cpp (100%) rename src/dynamics/{Thermal => thermal}/InitNode.hpp (100%) rename src/dynamics/{Thermal => thermal}/InitTemperature.cpp (100%) rename src/dynamics/{Thermal => thermal}/InitTemperature.hpp (100%) rename src/dynamics/{Thermal => thermal}/Node.cpp (100%) rename src/dynamics/{Thermal => thermal}/Node.h (100%) rename src/dynamics/{Thermal => thermal}/Temperature.cpp (100%) rename src/dynamics/{Thermal => thermal}/Temperature.h (100%) diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index 6c858bf0a..c7db5f4fa 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -9,7 +9,7 @@ #define __STT_H__ #include -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index c5498af73..bb8cd39ab 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -6,7 +6,7 @@ #pragma once #include #include -#include +#include #include #include diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 91b282754..26ca06ac4 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -2,23 +2,23 @@ project(DYNAMICS) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Orbit/Orbit.cpp - Orbit/Sgp4OrbitPropagation.cpp - Orbit/Rk4OrbitPropagation.cpp - Orbit/RelativeOrbit.cpp - Orbit/KeplerOrbitPropagation.cpp - Orbit/EnckeOrbitPropagation.cpp - Orbit/InitOrbit.cpp + orbit/Orbit.cpp + orbit/Sgp4OrbitPropagation.cpp + orbit/Rk4OrbitPropagation.cpp + orbit/RelativeOrbit.cpp + orbit/KeplerOrbitPropagation.cpp + orbit/EnckeOrbitPropagation.cpp + orbit/InitOrbit.cpp - Thermal/Node.cpp - Thermal/Temperature.cpp - Thermal/InitNode.cpp - Thermal/InitTemperature.cpp + thermal/Node.cpp + thermal/Temperature.cpp + thermal/InitNode.cpp + thermal/InitTemperature.cpp - Attitude/Attitude.cpp - Attitude/AttitudeRK4.cpp - Attitude/ControlledAttitude.cpp - Attitude/InitAttitude.cpp + attitude/Attitude.cpp + attitude/AttitudeRK4.cpp + attitude/ControlledAttitude.cpp + attitude/InitAttitude.cpp dynamics.cpp ) diff --git a/src/dynamics/Attitude/Attitude.cpp b/src/dynamics/attitude/Attitude.cpp similarity index 100% rename from src/dynamics/Attitude/Attitude.cpp rename to src/dynamics/attitude/Attitude.cpp diff --git a/src/dynamics/Attitude/Attitude.h b/src/dynamics/attitude/Attitude.h similarity index 100% rename from src/dynamics/Attitude/Attitude.h rename to src/dynamics/attitude/Attitude.h diff --git a/src/dynamics/Attitude/AttitudeRK4.cpp b/src/dynamics/attitude/AttitudeRK4.cpp similarity index 100% rename from src/dynamics/Attitude/AttitudeRK4.cpp rename to src/dynamics/attitude/AttitudeRK4.cpp diff --git a/src/dynamics/Attitude/AttitudeRK4.h b/src/dynamics/attitude/AttitudeRK4.h similarity index 100% rename from src/dynamics/Attitude/AttitudeRK4.h rename to src/dynamics/attitude/AttitudeRK4.h diff --git a/src/dynamics/Attitude/ControlledAttitude.cpp b/src/dynamics/attitude/ControlledAttitude.cpp similarity index 100% rename from src/dynamics/Attitude/ControlledAttitude.cpp rename to src/dynamics/attitude/ControlledAttitude.cpp diff --git a/src/dynamics/Attitude/ControlledAttitude.h b/src/dynamics/attitude/ControlledAttitude.h similarity index 99% rename from src/dynamics/Attitude/ControlledAttitude.h rename to src/dynamics/attitude/ControlledAttitude.h index 7870d85d3..36857feff 100644 --- a/src/dynamics/Attitude/ControlledAttitude.h +++ b/src/dynamics/attitude/ControlledAttitude.h @@ -8,7 +8,7 @@ #include #include -#include "../Orbit/Orbit.h" +#include "../orbit/Orbit.h" #include "Attitude.h" /** diff --git a/src/dynamics/Attitude/InitAttitude.cpp b/src/dynamics/attitude/InitAttitude.cpp similarity index 100% rename from src/dynamics/Attitude/InitAttitude.cpp rename to src/dynamics/attitude/InitAttitude.cpp diff --git a/src/dynamics/Attitude/InitAttitude.hpp b/src/dynamics/attitude/InitAttitude.hpp similarity index 100% rename from src/dynamics/Attitude/InitAttitude.hpp rename to src/dynamics/attitude/InitAttitude.hpp diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index a0f7958b2..eedafcbd8 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -10,17 +10,17 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include -#include -#include -#include +#include +#include +#include +#include #include "../environment/global/simulation_time.hpp" #include "../environment/local/local_celestial_information.hpp" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" -#include "./Orbit/Orbit.h" -#include "./Thermal/Temperature.h" +#include "./orbit/Orbit.h" +#include "./thermal/Temperature.h" class RelativeInformation; diff --git a/src/dynamics/Orbit/EnckeOrbitPropagation.cpp b/src/dynamics/orbit/EnckeOrbitPropagation.cpp similarity index 100% rename from src/dynamics/Orbit/EnckeOrbitPropagation.cpp rename to src/dynamics/orbit/EnckeOrbitPropagation.cpp diff --git a/src/dynamics/Orbit/EnckeOrbitPropagation.h b/src/dynamics/orbit/EnckeOrbitPropagation.h similarity index 100% rename from src/dynamics/Orbit/EnckeOrbitPropagation.h rename to src/dynamics/orbit/EnckeOrbitPropagation.h diff --git a/src/dynamics/Orbit/InitOrbit.cpp b/src/dynamics/orbit/InitOrbit.cpp similarity index 100% rename from src/dynamics/Orbit/InitOrbit.cpp rename to src/dynamics/orbit/InitOrbit.cpp diff --git a/src/dynamics/Orbit/InitOrbit.hpp b/src/dynamics/orbit/InitOrbit.hpp similarity index 100% rename from src/dynamics/Orbit/InitOrbit.hpp rename to src/dynamics/orbit/InitOrbit.hpp diff --git a/src/dynamics/Orbit/KeplerOrbitPropagation.cpp b/src/dynamics/orbit/KeplerOrbitPropagation.cpp similarity index 100% rename from src/dynamics/Orbit/KeplerOrbitPropagation.cpp rename to src/dynamics/orbit/KeplerOrbitPropagation.cpp diff --git a/src/dynamics/Orbit/KeplerOrbitPropagation.h b/src/dynamics/orbit/KeplerOrbitPropagation.h similarity index 100% rename from src/dynamics/Orbit/KeplerOrbitPropagation.h rename to src/dynamics/orbit/KeplerOrbitPropagation.h diff --git a/src/dynamics/Orbit/Orbit.cpp b/src/dynamics/orbit/Orbit.cpp similarity index 100% rename from src/dynamics/Orbit/Orbit.cpp rename to src/dynamics/orbit/Orbit.cpp diff --git a/src/dynamics/Orbit/Orbit.h b/src/dynamics/orbit/Orbit.h similarity index 100% rename from src/dynamics/Orbit/Orbit.h rename to src/dynamics/orbit/Orbit.h diff --git a/src/dynamics/Orbit/RelativeOrbit.cpp b/src/dynamics/orbit/RelativeOrbit.cpp similarity index 100% rename from src/dynamics/Orbit/RelativeOrbit.cpp rename to src/dynamics/orbit/RelativeOrbit.cpp diff --git a/src/dynamics/Orbit/RelativeOrbit.h b/src/dynamics/orbit/RelativeOrbit.h similarity index 100% rename from src/dynamics/Orbit/RelativeOrbit.h rename to src/dynamics/orbit/RelativeOrbit.h diff --git a/src/dynamics/Orbit/Rk4OrbitPropagation.cpp b/src/dynamics/orbit/Rk4OrbitPropagation.cpp similarity index 100% rename from src/dynamics/Orbit/Rk4OrbitPropagation.cpp rename to src/dynamics/orbit/Rk4OrbitPropagation.cpp diff --git a/src/dynamics/Orbit/Rk4OrbitPropagation.h b/src/dynamics/orbit/Rk4OrbitPropagation.h similarity index 100% rename from src/dynamics/Orbit/Rk4OrbitPropagation.h rename to src/dynamics/orbit/Rk4OrbitPropagation.h diff --git a/src/dynamics/Orbit/Sgp4OrbitPropagation.cpp b/src/dynamics/orbit/Sgp4OrbitPropagation.cpp similarity index 100% rename from src/dynamics/Orbit/Sgp4OrbitPropagation.cpp rename to src/dynamics/orbit/Sgp4OrbitPropagation.cpp diff --git a/src/dynamics/Orbit/Sgp4OrbitPropagation.h b/src/dynamics/orbit/Sgp4OrbitPropagation.h similarity index 100% rename from src/dynamics/Orbit/Sgp4OrbitPropagation.h rename to src/dynamics/orbit/Sgp4OrbitPropagation.h diff --git a/src/dynamics/Thermal/InitNode.cpp b/src/dynamics/thermal/InitNode.cpp similarity index 100% rename from src/dynamics/Thermal/InitNode.cpp rename to src/dynamics/thermal/InitNode.cpp diff --git a/src/dynamics/Thermal/InitNode.hpp b/src/dynamics/thermal/InitNode.hpp similarity index 100% rename from src/dynamics/Thermal/InitNode.hpp rename to src/dynamics/thermal/InitNode.hpp diff --git a/src/dynamics/Thermal/InitTemperature.cpp b/src/dynamics/thermal/InitTemperature.cpp similarity index 100% rename from src/dynamics/Thermal/InitTemperature.cpp rename to src/dynamics/thermal/InitTemperature.cpp diff --git a/src/dynamics/Thermal/InitTemperature.hpp b/src/dynamics/thermal/InitTemperature.hpp similarity index 100% rename from src/dynamics/Thermal/InitTemperature.hpp rename to src/dynamics/thermal/InitTemperature.hpp diff --git a/src/dynamics/Thermal/Node.cpp b/src/dynamics/thermal/Node.cpp similarity index 100% rename from src/dynamics/Thermal/Node.cpp rename to src/dynamics/thermal/Node.cpp diff --git a/src/dynamics/Thermal/Node.h b/src/dynamics/thermal/Node.h similarity index 100% rename from src/dynamics/Thermal/Node.h rename to src/dynamics/thermal/Node.h diff --git a/src/dynamics/Thermal/Temperature.cpp b/src/dynamics/thermal/Temperature.cpp similarity index 100% rename from src/dynamics/Thermal/Temperature.cpp rename to src/dynamics/thermal/Temperature.cpp diff --git a/src/dynamics/Thermal/Temperature.h b/src/dynamics/thermal/Temperature.h similarity index 100% rename from src/dynamics/Thermal/Temperature.h rename to src/dynamics/thermal/Temperature.h diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index c6e5e6679..eb76fbb92 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,9 +4,9 @@ */ #include "local_environment.hpp" -#include -#include #include +#include +#include #include "initialize_local_environment.hpp" From 265bb8c876c08af5b0215ba3384862ceb3c332ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:24:40 +0100 Subject: [PATCH 0238/1086] Rename Attitude --- src/Component/AOCS/STT.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/attitude/AttitudeRK4.h | 2 +- src/dynamics/attitude/ControlledAttitude.h | 2 +- src/dynamics/attitude/InitAttitude.hpp | 2 +- src/dynamics/attitude/{Attitude.cpp => attitude.cpp} | 4 ++-- src/dynamics/attitude/{Attitude.h => attitude.hpp} | 9 +++++---- src/environment/local/local_environment.cpp | 3 ++- 9 files changed, 15 insertions(+), 13 deletions(-) rename src/dynamics/attitude/{Attitude.cpp => attitude.cpp} (97%) rename src/dynamics/attitude/{Attitude.h => attitude.hpp} (97%) diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index c7db5f4fa..e9e84aa1a 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -9,12 +9,12 @@ #define __STT_H__ #include -#include #include #include #include #include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index bb8cd39ab..6a28f7988 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -6,10 +6,10 @@ #pragma once #include #include -#include #include #include +#include #include #include #include diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 26ca06ac4..4ccb6d3cb 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -15,7 +15,7 @@ add_library(${PROJECT_NAME} STATIC thermal/InitNode.cpp thermal/InitTemperature.cpp - attitude/Attitude.cpp + attitude/attitude.cpp attitude/AttitudeRK4.cpp attitude/ControlledAttitude.cpp attitude/InitAttitude.cpp diff --git a/src/dynamics/attitude/AttitudeRK4.h b/src/dynamics/attitude/AttitudeRK4.h index 3d871586e..af790e112 100644 --- a/src/dynamics/attitude/AttitudeRK4.h +++ b/src/dynamics/attitude/AttitudeRK4.h @@ -5,7 +5,7 @@ #ifndef __attitude_rk4_H__ #define __attitude_rk4_H__ -#include "Attitude.h" +#include "attitude.hpp" /** * @class AttitudeRK4 diff --git a/src/dynamics/attitude/ControlledAttitude.h b/src/dynamics/attitude/ControlledAttitude.h index 36857feff..cc064c25a 100644 --- a/src/dynamics/attitude/ControlledAttitude.h +++ b/src/dynamics/attitude/ControlledAttitude.h @@ -9,7 +9,7 @@ #include #include "../orbit/Orbit.h" -#include "Attitude.h" +#include "attitude.hpp" /** * @enum AttCtrlMode diff --git a/src/dynamics/attitude/InitAttitude.hpp b/src/dynamics/attitude/InitAttitude.hpp index c38c0a099..78708883e 100644 --- a/src/dynamics/attitude/InitAttitude.hpp +++ b/src/dynamics/attitude/InitAttitude.hpp @@ -4,9 +4,9 @@ */ #pragma once -#include "Attitude.h" #include "AttitudeRK4.h" #include "ControlledAttitude.h" +#include "attitude.hpp" /** * @fn InitAttitude diff --git a/src/dynamics/attitude/Attitude.cpp b/src/dynamics/attitude/attitude.cpp similarity index 97% rename from src/dynamics/attitude/Attitude.cpp rename to src/dynamics/attitude/attitude.cpp index 91979cac2..b42ad2984 100644 --- a/src/dynamics/attitude/Attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -1,8 +1,8 @@ /** - * @file Attitude.cpp + * @file attitude.cpp * @brief Base class for attitude of spacecraft */ -#include "Attitude.h" +#include "attitude.hpp" #include diff --git a/src/dynamics/attitude/Attitude.h b/src/dynamics/attitude/attitude.hpp similarity index 97% rename from src/dynamics/attitude/Attitude.h rename to src/dynamics/attitude/attitude.hpp index 13b862968..d1f4e87fb 100644 --- a/src/dynamics/attitude/Attitude.h +++ b/src/dynamics/attitude/attitude.hpp @@ -1,9 +1,10 @@ /** - * @file Attitude.h + * @file attitude.hpp * @brief Base class for attitude of spacecraft */ -#ifndef __attitude_H__ -#define __attitude_H__ + +#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ +#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #include @@ -177,4 +178,4 @@ class Attitude : public ILoggable, public SimulationObject { void CalcSatRotationalKineticEnergy(void); }; -#endif //__attitude_H__ +#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index eb76fbb92..1382f9cc0 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -5,9 +5,10 @@ #include "local_environment.hpp" #include -#include #include +#include + #include "initialize_local_environment.hpp" LocalEnvironment::LocalEnvironment(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { From dd5774abcc094cc565d9604ec8261fea14f71973 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:29:10 +0100 Subject: [PATCH 0239/1086] Rename AttitudeRK4 --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/attitude/InitAttitude.hpp | 2 +- .../attitude/{AttitudeRK4.cpp => attitude_rk4.cpp} | 4 ++-- .../attitude/{AttitudeRK4.h => attitude_rk4.hpp} | 9 +++++---- 4 files changed, 9 insertions(+), 8 deletions(-) rename src/dynamics/attitude/{AttitudeRK4.cpp => attitude_rk4.cpp} (98%) rename src/dynamics/attitude/{AttitudeRK4.h => attitude_rk4.hpp} (93%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 4ccb6d3cb..a6f671f88 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -16,7 +16,7 @@ add_library(${PROJECT_NAME} STATIC thermal/InitTemperature.cpp attitude/attitude.cpp - attitude/AttitudeRK4.cpp + attitude/attitude_rk4.cpp attitude/ControlledAttitude.cpp attitude/InitAttitude.cpp diff --git a/src/dynamics/attitude/InitAttitude.hpp b/src/dynamics/attitude/InitAttitude.hpp index 78708883e..51b0213b3 100644 --- a/src/dynamics/attitude/InitAttitude.hpp +++ b/src/dynamics/attitude/InitAttitude.hpp @@ -4,9 +4,9 @@ */ #pragma once -#include "AttitudeRK4.h" #include "ControlledAttitude.h" #include "attitude.hpp" +#include "attitude_rk4.hpp" /** * @fn InitAttitude diff --git a/src/dynamics/attitude/AttitudeRK4.cpp b/src/dynamics/attitude/attitude_rk4.cpp similarity index 98% rename from src/dynamics/attitude/AttitudeRK4.cpp rename to src/dynamics/attitude/attitude_rk4.cpp index 764cd1f27..67e7f7ac1 100644 --- a/src/dynamics/attitude/AttitudeRK4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -1,8 +1,8 @@ /** - * @file AttitudeRK4.cpp + * @file attitude_rk4.cpp * @brief Class to calculate spacecraft attitude with Runge-Kutta method */ -#include "AttitudeRK4.h" +#include "attitude_rk4.hpp" #include diff --git a/src/dynamics/attitude/AttitudeRK4.h b/src/dynamics/attitude/attitude_rk4.hpp similarity index 93% rename from src/dynamics/attitude/AttitudeRK4.h rename to src/dynamics/attitude/attitude_rk4.hpp index af790e112..355463bd9 100644 --- a/src/dynamics/attitude/AttitudeRK4.h +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -1,9 +1,10 @@ /** - * @file AttitudeRK4.h + * @file attitude_rk4.hpp * @brief Class to calculate spacecraft attitude with Runge-Kutta method */ -#ifndef __attitude_rk4_H__ -#define __attitude_rk4_H__ + +#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ +#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ #include "attitude.hpp" @@ -82,4 +83,4 @@ class AttitudeRK4 : public Attitude { void RungeOneStep(double t, double dt); }; -#endif //__attitude_rk4_H__ +#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ From ccf49f5341a15f1ed8cfa80564c30a40e87b32df Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:38:54 +0100 Subject: [PATCH 0240/1086] Rename ControlledAttitude --- src/dynamics/CMakeLists.txt | 4 ++-- ...{ControlledAttitude.cpp => controlled_attitude.cpp} | 4 ++-- .../{ControlledAttitude.h => controlled_attitude.hpp} | 9 +++++---- .../{InitAttitude.cpp => initialize_attitude.cpp} | 4 ++-- .../{InitAttitude.hpp => initialize_attitude.hpp} | 10 +++++++--- src/dynamics/dynamics.hpp | 2 +- 6 files changed, 19 insertions(+), 14 deletions(-) rename src/dynamics/attitude/{ControlledAttitude.cpp => controlled_attitude.cpp} (98%) rename src/dynamics/attitude/{ControlledAttitude.h => controlled_attitude.hpp} (96%) rename src/dynamics/attitude/{InitAttitude.cpp => initialize_attitude.cpp} (97%) rename src/dynamics/attitude/{InitAttitude.hpp => initialize_attitude.hpp} (74%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index a6f671f88..f6aaff21d 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -17,8 +17,8 @@ add_library(${PROJECT_NAME} STATIC attitude/attitude.cpp attitude/attitude_rk4.cpp - attitude/ControlledAttitude.cpp - attitude/InitAttitude.cpp + attitude/controlled_attitude.cpp + attitude/initialize_attitude.cpp dynamics.cpp ) diff --git a/src/dynamics/attitude/ControlledAttitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp similarity index 98% rename from src/dynamics/attitude/ControlledAttitude.cpp rename to src/dynamics/attitude/controlled_attitude.cpp index e76f23e98..84c2273eb 100644 --- a/src/dynamics/attitude/ControlledAttitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -1,8 +1,8 @@ /** - * @file ControlledAttitude.h + * @file controlled_attitude.hpp * @brief Class to calculate spacecraft attitude with Controlled Attitude mode */ -#include "ControlledAttitude.h" +#include "controlled_attitude.hpp" #include diff --git a/src/dynamics/attitude/ControlledAttitude.h b/src/dynamics/attitude/controlled_attitude.hpp similarity index 96% rename from src/dynamics/attitude/ControlledAttitude.h rename to src/dynamics/attitude/controlled_attitude.hpp index cc064c25a..6005bb246 100644 --- a/src/dynamics/attitude/ControlledAttitude.h +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -1,9 +1,10 @@ /** - * @file ControlledAttitude.h + * @file controlled_attitude.hpp * @brief Class to calculate spacecraft attitude with Controlled Attitude mode */ -#ifndef __controlled_attitude_H__ -#define __controlled_attitude_H__ + +#ifndef S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ +#define S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ #include #include @@ -141,4 +142,4 @@ class ControlledAttitude : public Attitude { Matrix<3, 3> CalcDCM(const Vector<3> main_direction, const Vector<3> sub_direction); }; -#endif //__controlled_attitude_H__ +#endif // S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ diff --git a/src/dynamics/attitude/InitAttitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp similarity index 97% rename from src/dynamics/attitude/InitAttitude.cpp rename to src/dynamics/attitude/initialize_attitude.cpp index 30d04dff6..5e0a9b2c1 100644 --- a/src/dynamics/attitude/InitAttitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -1,8 +1,8 @@ /** - * @file InitAttitude.hpp + * @file initialize_attitude.hpp * @brief Initialize function for attitude */ -#include "InitAttitude.hpp" +#include "initialize_attitude.hpp" #include diff --git a/src/dynamics/attitude/InitAttitude.hpp b/src/dynamics/attitude/initialize_attitude.hpp similarity index 74% rename from src/dynamics/attitude/InitAttitude.hpp rename to src/dynamics/attitude/initialize_attitude.hpp index 51b0213b3..cae91bb09 100644 --- a/src/dynamics/attitude/InitAttitude.hpp +++ b/src/dynamics/attitude/initialize_attitude.hpp @@ -1,12 +1,14 @@ /** - * @file InitAttitude.hpp + * @file initialize_attitude.hpp * @brief Initialize function for attitude */ -#pragma once -#include "ControlledAttitude.h" +#ifndef S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ +#define S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ + #include "attitude.hpp" #include "attitude_rk4.hpp" +#include "controlled_attitude.hpp" /** * @fn InitAttitude @@ -20,3 +22,5 @@ */ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id); + +#endif // S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index eedafcbd8..ff435d3df 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -10,7 +10,7 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include +#include #include #include #include From 3d2ace2328416ebe2f75e641f1fa3eb200746f0e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:42:37 +0100 Subject: [PATCH 0241/1086] Rename EnckeOrbitPropagation --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/orbit/InitOrbit.cpp | 2 +- ...eOrbitPropagation.cpp => encke_orbit_propagation.cpp} | 4 ++-- ...ckeOrbitPropagation.h => encke_orbit_propagation.hpp} | 9 +++++++-- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{EnckeOrbitPropagation.cpp => encke_orbit_propagation.cpp} (98%) rename src/dynamics/orbit/{EnckeOrbitPropagation.h => encke_orbit_propagation.hpp} (94%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index f6aaff21d..bc481d94e 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -7,7 +7,7 @@ add_library(${PROJECT_NAME} STATIC orbit/Rk4OrbitPropagation.cpp orbit/RelativeOrbit.cpp orbit/KeplerOrbitPropagation.cpp - orbit/EnckeOrbitPropagation.cpp + orbit/encke_orbit_propagation.cpp orbit/InitOrbit.cpp thermal/Node.cpp diff --git a/src/dynamics/orbit/InitOrbit.cpp b/src/dynamics/orbit/InitOrbit.cpp index 1185b294e..7659db4e1 100644 --- a/src/dynamics/orbit/InitOrbit.cpp +++ b/src/dynamics/orbit/InitOrbit.cpp @@ -6,11 +6,11 @@ #include -#include "EnckeOrbitPropagation.h" #include "KeplerOrbitPropagation.h" #include "RelativeOrbit.h" #include "Rk4OrbitPropagation.h" #include "Sgp4OrbitPropagation.h" +#include "encke_orbit_propagation.hpp" Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { diff --git a/src/dynamics/orbit/EnckeOrbitPropagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp similarity index 98% rename from src/dynamics/orbit/EnckeOrbitPropagation.cpp rename to src/dynamics/orbit/encke_orbit_propagation.cpp index 954f6b81c..1fce730bd 100644 --- a/src/dynamics/orbit/EnckeOrbitPropagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -1,9 +1,9 @@ /** - * @file EnckeOrbitPropagation.cpp + * @file encke_orbit_propagation.cpp * @brief Class to propagate spacecraft orbit with Encke's method */ -#include "EnckeOrbitPropagation.h" +#include "encke_orbit_propagation.hpp" #include diff --git a/src/dynamics/orbit/EnckeOrbitPropagation.h b/src/dynamics/orbit/encke_orbit_propagation.hpp similarity index 94% rename from src/dynamics/orbit/EnckeOrbitPropagation.h rename to src/dynamics/orbit/encke_orbit_propagation.hpp index a72354242..1c76f0194 100644 --- a/src/dynamics/orbit/EnckeOrbitPropagation.h +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -1,8 +1,11 @@ /** - * @file EnckeOrbitPropagation.h + * @file encke_orbit_propagation.hpp * @brief Class to propagate spacecraft orbit with Encke's method */ -#pragma once + +#ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ +#define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ + #include "../../Library/Orbit/KeplerOrbit.h" #include "../../Library/math/ODE.hpp" #include "Orbit.h" @@ -88,3 +91,5 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { */ double CalcQFunction(Vector<3> diff_pos_i); }; + +#endif // S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ From bd267ad81682fcf143f3759ac10319d871b70b63 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:45:09 +0100 Subject: [PATCH 0242/1086] Rename Orbit --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/attitude/controlled_attitude.hpp | 2 +- src/dynamics/dynamics.hpp | 2 +- src/dynamics/orbit/InitOrbit.hpp | 2 +- src/dynamics/orbit/KeplerOrbitPropagation.h | 2 +- src/dynamics/orbit/RelativeOrbit.h | 2 +- src/dynamics/orbit/Rk4OrbitPropagation.h | 2 +- src/dynamics/orbit/Sgp4OrbitPropagation.h | 2 +- src/dynamics/orbit/encke_orbit_propagation.hpp | 2 +- src/dynamics/orbit/{Orbit.cpp => orbit.cpp} | 4 ++-- src/dynamics/orbit/{Orbit.h => orbit.hpp} | 9 +++++---- src/environment/local/local_environment.cpp | 2 +- 12 files changed, 17 insertions(+), 16 deletions(-) rename src/dynamics/orbit/{Orbit.cpp => orbit.cpp} (98%) rename src/dynamics/orbit/{Orbit.h => orbit.hpp} (98%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index bc481d94e..7cb561717 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -2,7 +2,7 @@ project(DYNAMICS) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - orbit/Orbit.cpp + orbit/orbit.cpp orbit/Sgp4OrbitPropagation.cpp orbit/Rk4OrbitPropagation.cpp orbit/RelativeOrbit.cpp diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 6005bb246..54044c660 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -9,7 +9,7 @@ #include #include -#include "../orbit/Orbit.h" +#include "../orbit/orbit.hpp" #include "attitude.hpp" /** diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index ff435d3df..5b331bffc 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -19,7 +19,7 @@ using libra::Vector; #include "../environment/local/local_celestial_information.hpp" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" -#include "./orbit/Orbit.h" +#include "./orbit/orbit.hpp" #include "./thermal/Temperature.h" class RelativeInformation; diff --git a/src/dynamics/orbit/InitOrbit.hpp b/src/dynamics/orbit/InitOrbit.hpp index 70f3fc05c..17ee5d024 100644 --- a/src/dynamics/orbit/InitOrbit.hpp +++ b/src/dynamics/orbit/InitOrbit.hpp @@ -6,7 +6,7 @@ #include -#include "Orbit.h" +#include "orbit.hpp" class RelativeInformation; diff --git a/src/dynamics/orbit/KeplerOrbitPropagation.h b/src/dynamics/orbit/KeplerOrbitPropagation.h index 22b64c36a..b3200f5d6 100644 --- a/src/dynamics/orbit/KeplerOrbitPropagation.h +++ b/src/dynamics/orbit/KeplerOrbitPropagation.h @@ -4,7 +4,7 @@ */ #pragma once #include "../../Library/Orbit/KeplerOrbit.h" -#include "Orbit.h" +#include "orbit.hpp" /** * @class KeplerOrbitPropagation diff --git a/src/dynamics/orbit/RelativeOrbit.h b/src/dynamics/orbit/RelativeOrbit.h index bd073dd72..8dc36de44 100644 --- a/src/dynamics/orbit/RelativeOrbit.h +++ b/src/dynamics/orbit/RelativeOrbit.h @@ -9,7 +9,7 @@ #include #include -#include "Orbit.h" +#include "orbit.hpp" /** * @class RelativeOrbit diff --git a/src/dynamics/orbit/Rk4OrbitPropagation.h b/src/dynamics/orbit/Rk4OrbitPropagation.h index c35121aa0..bab858ee4 100644 --- a/src/dynamics/orbit/Rk4OrbitPropagation.h +++ b/src/dynamics/orbit/Rk4OrbitPropagation.h @@ -5,7 +5,7 @@ #include #include -#include "Orbit.h" +#include "orbit.hpp" /** * @class Rk4OrbitPropagation diff --git a/src/dynamics/orbit/Sgp4OrbitPropagation.h b/src/dynamics/orbit/Sgp4OrbitPropagation.h index 22b2c45ec..1c19c0426 100644 --- a/src/dynamics/orbit/Sgp4OrbitPropagation.h +++ b/src/dynamics/orbit/Sgp4OrbitPropagation.h @@ -8,7 +8,7 @@ #include -#include "Orbit.h" +#include "orbit.hpp" /** * @class Sgp4OrbitPropagation diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 1c76f0194..90fc7b4fa 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -8,7 +8,7 @@ #include "../../Library/Orbit/KeplerOrbit.h" #include "../../Library/math/ODE.hpp" -#include "Orbit.h" +#include "orbit.hpp" /** * @class EnckeOrbitPropagation diff --git a/src/dynamics/orbit/Orbit.cpp b/src/dynamics/orbit/orbit.cpp similarity index 98% rename from src/dynamics/orbit/Orbit.cpp rename to src/dynamics/orbit/orbit.cpp index 675a6c628..dec0509c7 100644 --- a/src/dynamics/orbit/Orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -1,8 +1,8 @@ /** - * @file Orbit.cpp + * @file orbit.cpp * @brief Base class of orbit propagation */ -#include "Orbit.h" +#include "orbit.hpp" Quaternion Orbit::CalcQuaternionI2LVLH() const { Vector<3> lvlh_x = sat_position_i_; // x-axis in LVLH frame is position vector direction from geocenter to satellite diff --git a/src/dynamics/orbit/Orbit.h b/src/dynamics/orbit/orbit.hpp similarity index 98% rename from src/dynamics/orbit/Orbit.h rename to src/dynamics/orbit/orbit.hpp index 6ec82c2f1..2536ddf29 100644 --- a/src/dynamics/orbit/Orbit.h +++ b/src/dynamics/orbit/orbit.hpp @@ -1,9 +1,10 @@ /** - * @file Orbit.h + * @file orbit.hpp * @brief Base class of orbit propagation */ -#ifndef __orbit_H__ -#define __orbit_H__ + +#ifndef S2E_DYNAMICS_ORBIT_ORBIT_H_ +#define S2E_DYNAMICS_ORBIT_ORBIT_H_ #include #include @@ -227,4 +228,4 @@ class Orbit : public ILoggable { OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode); -#endif //__orbit_H__ +#endif // S2E_DYNAMICS_ORBIT_ORBIT_H_ diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 1382f9cc0..5747b4cca 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -5,7 +5,7 @@ #include "local_environment.hpp" #include -#include +#include #include From cc0ea0bcd218697860e926522264a4749e87ba8f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 16:49:33 +0100 Subject: [PATCH 0243/1086] Rename InitOrbit --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/dynamics.hpp | 2 +- .../orbit/{InitOrbit.cpp => initialize_orbit.cpp} | 4 ++-- .../orbit/{InitOrbit.hpp => initialize_orbit.hpp} | 8 ++++++-- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{InitOrbit.cpp => initialize_orbit.cpp} (99%) rename src/dynamics/orbit/{InitOrbit.hpp => initialize_orbit.hpp} (87%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 7cb561717..1b652a12a 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -8,7 +8,7 @@ add_library(${PROJECT_NAME} STATIC orbit/RelativeOrbit.cpp orbit/KeplerOrbitPropagation.cpp orbit/encke_orbit_propagation.cpp - orbit/InitOrbit.cpp + orbit/initialize_orbit.cpp thermal/Node.cpp thermal/Temperature.cpp diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 5b331bffc..e9b4ec00d 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -11,7 +11,7 @@ using libra::Vector; #include -#include +#include #include #include diff --git a/src/dynamics/orbit/InitOrbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp similarity index 99% rename from src/dynamics/orbit/InitOrbit.cpp rename to src/dynamics/orbit/initialize_orbit.cpp index 7659db4e1..108205aee 100644 --- a/src/dynamics/orbit/InitOrbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -1,8 +1,8 @@ /** - * @file InitOrbit.cpp + * @file initialize_orbit.cpp * @brief Initialize function for Orbit class */ -#include "InitOrbit.hpp" +#include "initialize_orbit.hpp" #include diff --git a/src/dynamics/orbit/InitOrbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp similarity index 87% rename from src/dynamics/orbit/InitOrbit.hpp rename to src/dynamics/orbit/initialize_orbit.hpp index 17ee5d024..b08d2fca2 100644 --- a/src/dynamics/orbit/InitOrbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -1,8 +1,10 @@ /** - * @file InitOrbit.h + * @file initialize_orbit.hpp * @brief Initialize function for Orbit class */ -#pragma once + +#ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ +#define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ #include @@ -33,3 +35,5 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d * @param [in] section: Section name */ Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3_s2, std::string section = "ORBIT"); + +#endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ From 682f1cef86f7f6b28e2984e257a82d700fc98b71 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 19:43:18 +0100 Subject: [PATCH 0244/1086] Rename KeplerOrbitPropagation --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- ...OrbitPropagation.cpp => kepler_orbit_propagation.cpp} | 4 ++-- ...erOrbitPropagation.h => kepler_orbit_propagation.hpp} | 9 +++++++-- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{KeplerOrbitPropagation.cpp => kepler_orbit_propagation.cpp} (91%) rename src/dynamics/orbit/{KeplerOrbitPropagation.h => kepler_orbit_propagation.hpp} (85%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 1b652a12a..8be052037 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC orbit/Sgp4OrbitPropagation.cpp orbit/Rk4OrbitPropagation.cpp orbit/RelativeOrbit.cpp - orbit/KeplerOrbitPropagation.cpp + orbit/kepler_orbit_propagation.cpp orbit/encke_orbit_propagation.cpp orbit/initialize_orbit.cpp diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 108205aee..b644d4e7b 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -6,11 +6,11 @@ #include -#include "KeplerOrbitPropagation.h" #include "RelativeOrbit.h" #include "Rk4OrbitPropagation.h" #include "Sgp4OrbitPropagation.h" #include "encke_orbit_propagation.hpp" +#include "kepler_orbit_propagation.hpp" Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { diff --git a/src/dynamics/orbit/KeplerOrbitPropagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp similarity index 91% rename from src/dynamics/orbit/KeplerOrbitPropagation.cpp rename to src/dynamics/orbit/kepler_orbit_propagation.cpp index 956765e94..c3c4e213b 100644 --- a/src/dynamics/orbit/KeplerOrbitPropagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -1,8 +1,8 @@ /** - * @file KeplerOrbitPropagation.cpp + * @file kepler_orbit_propagation.cpp * @brief Class to propagate spacecraft orbit with Kepler equation */ -#include "KeplerOrbitPropagation.h" +#include "kepler_orbit_propagation.hpp" #include diff --git a/src/dynamics/orbit/KeplerOrbitPropagation.h b/src/dynamics/orbit/kepler_orbit_propagation.hpp similarity index 85% rename from src/dynamics/orbit/KeplerOrbitPropagation.h rename to src/dynamics/orbit/kepler_orbit_propagation.hpp index b3200f5d6..95b64aa1a 100644 --- a/src/dynamics/orbit/KeplerOrbitPropagation.h +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -1,8 +1,11 @@ /** - * @file KeplerOrbitPropagation.h + * @file kepler_orbit_propagation.hpp * @brief Class to propagate spacecraft orbit with Kepler equation */ -#pragma once + +#ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ +#define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ + #include "../../Library/Orbit/KeplerOrbit.h" #include "orbit.hpp" @@ -44,3 +47,5 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { */ void UpdateState(const double current_jd); }; + +#endif // S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ From f825f7fc833852ea9e5f7db96db1a6dbc17d38bc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 19:47:05 +0100 Subject: [PATCH 0245/1086] Rename RelativeOrbit --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- .../orbit/{RelativeOrbit.cpp => relative_orbit.cpp} | 4 ++-- .../orbit/{RelativeOrbit.h => relative_orbit.hpp} | 9 +++++++-- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{RelativeOrbit.cpp => relative_orbit.cpp} (99%) rename src/dynamics/orbit/{RelativeOrbit.h => relative_orbit.hpp} (96%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 8be052037..f8fbb986b 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC orbit/orbit.cpp orbit/Sgp4OrbitPropagation.cpp orbit/Rk4OrbitPropagation.cpp - orbit/RelativeOrbit.cpp + orbit/relative_orbit.cpp orbit/kepler_orbit_propagation.cpp orbit/encke_orbit_propagation.cpp orbit/initialize_orbit.cpp diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index b644d4e7b..d09498c85 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -6,11 +6,11 @@ #include -#include "RelativeOrbit.h" #include "Rk4OrbitPropagation.h" #include "Sgp4OrbitPropagation.h" #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" +#include "relative_orbit.hpp" Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { diff --git a/src/dynamics/orbit/RelativeOrbit.cpp b/src/dynamics/orbit/relative_orbit.cpp similarity index 99% rename from src/dynamics/orbit/RelativeOrbit.cpp rename to src/dynamics/orbit/relative_orbit.cpp index 24bd8ab7b..aac5ab7bd 100644 --- a/src/dynamics/orbit/RelativeOrbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -1,8 +1,8 @@ /** - * @file RelativeOrbit.cpp + * @file relative_orbit.cpp * @brief Class to propagate relative orbit */ -#include "RelativeOrbit.h" +#include "relative_orbit.hpp" #include diff --git a/src/dynamics/orbit/RelativeOrbit.h b/src/dynamics/orbit/relative_orbit.hpp similarity index 96% rename from src/dynamics/orbit/RelativeOrbit.h rename to src/dynamics/orbit/relative_orbit.hpp index 8dc36de44..032011580 100644 --- a/src/dynamics/orbit/RelativeOrbit.h +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -1,8 +1,11 @@ /** - * @file RelativeOrbit.h + * @file relative_orbit.hpp * @brief Class to propagate relative orbit */ -#pragma once + +#ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ +#define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ + #include #include @@ -121,3 +124,5 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { */ void PropagateSTM(double elapsed_sec); }; + +#endif // S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ From 1c330c109b6e1e71dfac22b8933a125f8aeee96c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 19:50:05 +0100 Subject: [PATCH 0246/1086] Rename Rk4OrbitPropagation --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/orbit/relative_orbit.cpp | 2 +- ...{Rk4OrbitPropagation.cpp => rk4_orbit_propagation.cpp} | 4 ++-- .../{Rk4OrbitPropagation.h => rk4_orbit_propagation.hpp} | 8 +++++++- 5 files changed, 12 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{Rk4OrbitPropagation.cpp => rk4_orbit_propagation.cpp} (97%) rename src/dynamics/orbit/{Rk4OrbitPropagation.h => rk4_orbit_propagation.hpp} (92%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index f8fbb986b..2e7594a74 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC orbit/orbit.cpp orbit/Sgp4OrbitPropagation.cpp - orbit/Rk4OrbitPropagation.cpp + orbit/rk4_orbit_propagation.cpp orbit/relative_orbit.cpp orbit/kepler_orbit_propagation.cpp orbit/encke_orbit_propagation.cpp diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index d09498c85..ff0bd5d6b 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -6,11 +6,11 @@ #include -#include "Rk4OrbitPropagation.h" #include "Sgp4OrbitPropagation.h" #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" #include "relative_orbit.hpp" +#include "rk4_orbit_propagation.hpp" Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index aac5ab7bd..49c771dd2 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -6,7 +6,7 @@ #include -#include "Rk4OrbitPropagation.h" +#include "rk4_orbit_propagation.hpp" RelativeOrbit::RelativeOrbit(const CelestialInformation* celes_info, double mu, double timestep, int reference_sat_id, Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, diff --git a/src/dynamics/orbit/Rk4OrbitPropagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp similarity index 97% rename from src/dynamics/orbit/Rk4OrbitPropagation.cpp rename to src/dynamics/orbit/rk4_orbit_propagation.cpp index 9f02a1ac0..451d85421 100644 --- a/src/dynamics/orbit/Rk4OrbitPropagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -1,8 +1,8 @@ /** - * @file Rk4OrbitPropagation.cpp + * @file rk4_orbit_propagation.cpp * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -#include "Rk4OrbitPropagation.h" +#include "rk4_orbit_propagation.hpp" #include #include diff --git a/src/dynamics/orbit/Rk4OrbitPropagation.h b/src/dynamics/orbit/rk4_orbit_propagation.hpp similarity index 92% rename from src/dynamics/orbit/Rk4OrbitPropagation.h rename to src/dynamics/orbit/rk4_orbit_propagation.hpp index bab858ee4..0dbfcf22b 100644 --- a/src/dynamics/orbit/Rk4OrbitPropagation.h +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -1,7 +1,11 @@ /** - * @file Rk4OrbitPropagation.h + * @file rk4_orbit_propagation.hpp * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ + +#ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ +#define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ + #include #include @@ -75,3 +79,5 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { */ void Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); }; + +#endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ From dba1f4208fb64f013bab132c51ad985932e22125 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 19:52:35 +0100 Subject: [PATCH 0247/1086] Rename Sgp4OrbitPropagation --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- ...p4OrbitPropagation.cpp => sgp4_orbit_propagation.cpp} | 4 ++-- ...Sgp4OrbitPropagation.h => sgp4_orbit_propagation.hpp} | 9 +++++++-- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/dynamics/orbit/{Sgp4OrbitPropagation.cpp => sgp4_orbit_propagation.cpp} (97%) rename src/dynamics/orbit/{Sgp4OrbitPropagation.h => sgp4_orbit_propagation.hpp} (87%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 2e7594a74..0300e0cc9 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC orbit/orbit.cpp - orbit/Sgp4OrbitPropagation.cpp + orbit/sgp4_orbit_propagation.cpp orbit/rk4_orbit_propagation.cpp orbit/relative_orbit.cpp orbit/kepler_orbit_propagation.cpp diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index ff0bd5d6b..ca9ae4d80 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -6,11 +6,11 @@ #include -#include "Sgp4OrbitPropagation.h" #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" #include "relative_orbit.hpp" #include "rk4_orbit_propagation.hpp" +#include "sgp4_orbit_propagation.hpp" Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { diff --git a/src/dynamics/orbit/Sgp4OrbitPropagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp similarity index 97% rename from src/dynamics/orbit/Sgp4OrbitPropagation.cpp rename to src/dynamics/orbit/sgp4_orbit_propagation.cpp index 9ca035e8b..2dbc985ea 100644 --- a/src/dynamics/orbit/Sgp4OrbitPropagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -1,9 +1,9 @@ /** - * @file Sgp4OrbitPropagation.cpp + * @file sgp4_orbit_propagation.cpp * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ -#include "Sgp4OrbitPropagation.h" +#include "sgp4_orbit_propagation.hpp" #include #include diff --git a/src/dynamics/orbit/Sgp4OrbitPropagation.h b/src/dynamics/orbit/sgp4_orbit_propagation.hpp similarity index 87% rename from src/dynamics/orbit/Sgp4OrbitPropagation.h rename to src/dynamics/orbit/sgp4_orbit_propagation.hpp index 1c19c0426..7b9e8ea51 100644 --- a/src/dynamics/orbit/Sgp4OrbitPropagation.h +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -1,8 +1,11 @@ /** - * @file Sgp4OrbitPropagation.h + * @file sgp4_orbit_propagation.hpp * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ -#pragma once + +#ifndef S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ +#define S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ + #include #include @@ -48,3 +51,5 @@ class Sgp4OrbitPropagation : public Orbit { elsetrec satrec_; //!< Structure data for SGP4 library const CelestialInformation* celes_info_; //!< Celestial information }; + +#endif // S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ From f183c1f93ae55b3df06617b1d137a380de9d9256 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:35:03 +0100 Subject: [PATCH 0248/1086] Rename InitNode --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/dynamics.hpp | 2 +- src/dynamics/thermal/InitNode.hpp | 5 ----- src/dynamics/thermal/InitTemperature.cpp | 2 +- .../thermal/{InitNode.cpp => initialize_node.cpp} | 9 +++++++-- src/dynamics/thermal/initialize_node.hpp | 13 +++++++++++++ 6 files changed, 23 insertions(+), 10 deletions(-) delete mode 100644 src/dynamics/thermal/InitNode.hpp rename src/dynamics/thermal/{InitNode.cpp => initialize_node.cpp} (91%) create mode 100644 src/dynamics/thermal/initialize_node.hpp diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 0300e0cc9..b904634af 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -12,7 +12,7 @@ add_library(${PROJECT_NAME} STATIC thermal/Node.cpp thermal/Temperature.cpp - thermal/InitNode.cpp + thermal/initialize_node.cpp thermal/InitTemperature.cpp attitude/attitude.cpp diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index e9b4ec00d..fc9a4bb38 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -12,8 +12,8 @@ using libra::Vector; #include #include -#include #include +#include #include "../environment/global/simulation_time.hpp" #include "../environment/local/local_celestial_information.hpp" diff --git a/src/dynamics/thermal/InitNode.hpp b/src/dynamics/thermal/InitNode.hpp deleted file mode 100644 index 5a720712c..000000000 --- a/src/dynamics/thermal/InitNode.hpp +++ /dev/null @@ -1,5 +0,0 @@ -#pragma once - -#include "Node.h" - -Node InitNode(const std::vector& node_str); diff --git a/src/dynamics/thermal/InitTemperature.cpp b/src/dynamics/thermal/InitTemperature.cpp index 439e182e2..9ec63a294 100644 --- a/src/dynamics/thermal/InitTemperature.cpp +++ b/src/dynamics/thermal/InitTemperature.cpp @@ -5,7 +5,7 @@ #include #include -#include "InitNode.hpp" +#include "initialize_node.hpp" /* Import node properties and Cij/Rij Datas by reading CSV File (node.csv, cij.csv, rij.csv) Detailed process of reading node properties from CSV File, and diff --git a/src/dynamics/thermal/InitNode.cpp b/src/dynamics/thermal/initialize_node.cpp similarity index 91% rename from src/dynamics/thermal/InitNode.cpp rename to src/dynamics/thermal/initialize_node.cpp index 5f266db67..6410298f9 100644 --- a/src/dynamics/thermal/InitNode.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -1,4 +1,9 @@ -#include "InitNode.hpp" +/** + * @file initialize_node.cpp + * @brief Initialize function for node + */ + +#include "initialize_node.hpp" #include @@ -7,7 +12,7 @@ #include #include -/* Import node properties and Cij/Rij Datas by reading CSV File (Node.csv, +/* Import node properties and Cij/Rij Data by reading CSV File (Node.csv, Cij.csv, Rij.csv) Detailed process of reading node properties from CSV File, and CSV file formats of node properties is written in Init_Node.cpp diff --git a/src/dynamics/thermal/initialize_node.hpp b/src/dynamics/thermal/initialize_node.hpp new file mode 100644 index 000000000..e6c448dfb --- /dev/null +++ b/src/dynamics/thermal/initialize_node.hpp @@ -0,0 +1,13 @@ +/** + * @file initialize_node.hpp + * @brief Initialize function for node + */ + +#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ +#define S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ + +#include "Node.h" + +Node InitNode(const std::vector& node_str); + +#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ From c0ca6cdab31e4f37a6743cb675a7de6c48ad67c8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:38:04 +0100 Subject: [PATCH 0249/1086] Rename InitTemperature --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/dynamics.hpp | 2 +- src/dynamics/thermal/InitTemperature.hpp | 6 ------ ...tTemperature.cpp => initialize_temperature.cpp} | 2 +- src/dynamics/thermal/initialize_temperature.hpp | 14 ++++++++++++++ 5 files changed, 17 insertions(+), 9 deletions(-) delete mode 100644 src/dynamics/thermal/InitTemperature.hpp rename src/dynamics/thermal/{InitTemperature.cpp => initialize_temperature.cpp} (98%) create mode 100644 src/dynamics/thermal/initialize_temperature.hpp diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index b904634af..ed86e9bcd 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -13,7 +13,7 @@ add_library(${PROJECT_NAME} STATIC thermal/Node.cpp thermal/Temperature.cpp thermal/initialize_node.cpp - thermal/InitTemperature.cpp + thermal/initialize_temperature.cpp attitude/attitude.cpp attitude/attitude_rk4.cpp diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index fc9a4bb38..e5e64e31c 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -12,8 +12,8 @@ using libra::Vector; #include #include -#include #include +#include #include "../environment/global/simulation_time.hpp" #include "../environment/local/local_celestial_information.hpp" diff --git a/src/dynamics/thermal/InitTemperature.hpp b/src/dynamics/thermal/InitTemperature.hpp deleted file mode 100644 index ef9ceb185..000000000 --- a/src/dynamics/thermal/InitTemperature.hpp +++ /dev/null @@ -1,6 +0,0 @@ -#pragma once - -#include "Temperature.h" -class Temperature; - -Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec); diff --git a/src/dynamics/thermal/InitTemperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp similarity index 98% rename from src/dynamics/thermal/InitTemperature.cpp rename to src/dynamics/thermal/initialize_temperature.cpp index 9ec63a294..e8f8f9c8f 100644 --- a/src/dynamics/thermal/InitTemperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -1,4 +1,4 @@ -#include "InitTemperature.hpp" +#include "initialize_temperature.hpp" #include diff --git a/src/dynamics/thermal/initialize_temperature.hpp b/src/dynamics/thermal/initialize_temperature.hpp new file mode 100644 index 000000000..fa4258d93 --- /dev/null +++ b/src/dynamics/thermal/initialize_temperature.hpp @@ -0,0 +1,14 @@ +/** + * @file initialize_temperature.hpp + * @brief Initialize function for temperature + */ + +#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ +#define S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ + +#include "Temperature.h" +class Temperature; + +Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec); + +#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ From 9d5335ea97698d201f85a0b0ccb23a777cd15ab0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:41:14 +0100 Subject: [PATCH 0250/1086] Rename Node --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/thermal/Temperature.h | 2 +- src/dynamics/thermal/initialize_node.hpp | 2 +- .../thermal/initialize_temperature.cpp | 5 +++++ src/dynamics/thermal/{Node.cpp => node.cpp} | 7 ++++++- src/dynamics/thermal/{Node.h => node.hpp} | 20 +++++++++++-------- 6 files changed, 26 insertions(+), 12 deletions(-) rename src/dynamics/thermal/{Node.cpp => node.cpp} (97%) rename src/dynamics/thermal/{Node.h => node.hpp} (69%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index ed86e9bcd..33b0adbf8 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -10,7 +10,7 @@ add_library(${PROJECT_NAME} STATIC orbit/encke_orbit_propagation.cpp orbit/initialize_orbit.cpp - thermal/Node.cpp + thermal/node.cpp thermal/Temperature.cpp thermal/initialize_node.cpp thermal/initialize_temperature.cpp diff --git a/src/dynamics/thermal/Temperature.h b/src/dynamics/thermal/Temperature.h index 230b8184d..98e23a417 100644 --- a/src/dynamics/thermal/Temperature.h +++ b/src/dynamics/thermal/Temperature.h @@ -8,7 +8,7 @@ #include #include -#include "Node.h" +#include "node.hpp" class Temperature : public ILoggable { protected: diff --git a/src/dynamics/thermal/initialize_node.hpp b/src/dynamics/thermal/initialize_node.hpp index e6c448dfb..58eb0eed9 100644 --- a/src/dynamics/thermal/initialize_node.hpp +++ b/src/dynamics/thermal/initialize_node.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ #define S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ -#include "Node.h" +#include "node.hpp" Node InitNode(const std::vector& node_str); diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index e8f8f9c8f..89d9dd9b0 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -1,3 +1,8 @@ +/** + * @file initialize_temperature.cpp + * @brief Initialize function for temperature + */ + #include "initialize_temperature.hpp" #include diff --git a/src/dynamics/thermal/Node.cpp b/src/dynamics/thermal/node.cpp similarity index 97% rename from src/dynamics/thermal/Node.cpp rename to src/dynamics/thermal/node.cpp index daf67c3f0..f4e88a40b 100644 --- a/src/dynamics/thermal/Node.cpp +++ b/src/dynamics/thermal/node.cpp @@ -1,4 +1,9 @@ -#include "Node.h" +/** + * @file node.cpp + * @brief thermal calculation node + */ + +#include "node.hpp" #include #include diff --git a/src/dynamics/thermal/Node.h b/src/dynamics/thermal/node.hpp similarity index 69% rename from src/dynamics/thermal/Node.h rename to src/dynamics/thermal/node.hpp index ddc33262d..b9c4b4ba1 100644 --- a/src/dynamics/thermal/Node.h +++ b/src/dynamics/thermal/node.hpp @@ -1,7 +1,10 @@ -#pragma once +/** + * @file node.hpp + * @brief thermal calculation node + */ -#ifndef __node_H__ -#define __node_H__ +#ifndef S2E_DYNAMICS_THERMAL_NODE_H_ +#define S2E_DYNAMICS_THERMAL_NODE_H_ #include @@ -17,9 +20,9 @@ class Node { double capacity_; // 熱容量[J/K] double internal_heat_; // 内部生成熱[J] double alpha_; - double area_; //太陽熱が入射する面の面積[m^2] - Vector<3> normal_v_b_; //太陽熱が入射する面の法線ベクトル(機体固定座標系) - double solar_radiation_; //入射する太陽輻射熱[W]([J]に変換するためには時間をかけないといけないことに注意 + double area_; // 太陽熱が入射する面の面積[m^2] + Vector<3> normal_v_b_; // 太陽熱が入射する面の法線ベクトル(機体固定座標系) + double solar_radiation_; // 入射する太陽輻射熱[W]([J]に変換するためには時間をかけないといけないことに注意 double K2deg(double kelvin) const; // 絶対温度からdegCに変換 @@ -43,9 +46,10 @@ class Node { // Setter void SetTemperature_K(double temp_K); - void SetInternalHeat(double heat_power); //内部発熱を計算 + void SetInternalHeat(double heat_power); // 内部発熱を計算 // for debug void PrintParam(void); }; -#endif //__node_H__ + +#endif // S2E_DYNAMICS_THERMAL_NODE_H_ From 2eed721a35ded9546133870c3ff7e5c3aeb92161 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:43:49 +0100 Subject: [PATCH 0251/1086] Rename temperature --- src/dynamics/CMakeLists.txt | 2 +- src/dynamics/dynamics.hpp | 2 +- src/dynamics/thermal/initialize_temperature.hpp | 2 +- .../thermal/{Temperature.cpp => temperature.cpp} | 7 ++++++- .../thermal/{Temperature.h => temperature.hpp} | 16 ++++++++++------ 5 files changed, 19 insertions(+), 10 deletions(-) rename src/dynamics/thermal/{Temperature.cpp => temperature.cpp} (98%) rename src/dynamics/thermal/{Temperature.h => temperature.hpp} (81%) diff --git a/src/dynamics/CMakeLists.txt b/src/dynamics/CMakeLists.txt index 33b0adbf8..f29b7e720 100644 --- a/src/dynamics/CMakeLists.txt +++ b/src/dynamics/CMakeLists.txt @@ -11,7 +11,7 @@ add_library(${PROJECT_NAME} STATIC orbit/initialize_orbit.cpp thermal/node.cpp - thermal/Temperature.cpp + thermal/temperature.cpp thermal/initialize_node.cpp thermal/initialize_temperature.cpp diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index e5e64e31c..21c16352d 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -20,7 +20,7 @@ using libra::Vector; #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" #include "./orbit/orbit.hpp" -#include "./thermal/Temperature.h" +#include "./thermal/temperature.hpp" class RelativeInformation; diff --git a/src/dynamics/thermal/initialize_temperature.hpp b/src/dynamics/thermal/initialize_temperature.hpp index fa4258d93..bd76de01b 100644 --- a/src/dynamics/thermal/initialize_temperature.hpp +++ b/src/dynamics/thermal/initialize_temperature.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ #define S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ -#include "Temperature.h" +#include "temperature.hpp" class Temperature; Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec); diff --git a/src/dynamics/thermal/Temperature.cpp b/src/dynamics/thermal/temperature.cpp similarity index 98% rename from src/dynamics/thermal/Temperature.cpp rename to src/dynamics/thermal/temperature.cpp index 7a5ca3768..a809ae508 100644 --- a/src/dynamics/thermal/Temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -1,4 +1,9 @@ -#include "Temperature.h" +/** + * @file temperature.hpp + * @brief Initialize temperature + */ + +#include "temperature.hpp" #include #include diff --git a/src/dynamics/thermal/Temperature.h b/src/dynamics/thermal/temperature.hpp similarity index 81% rename from src/dynamics/thermal/Temperature.h rename to src/dynamics/thermal/temperature.hpp index 98e23a417..44fd33fbf 100644 --- a/src/dynamics/thermal/Temperature.h +++ b/src/dynamics/thermal/temperature.hpp @@ -1,7 +1,10 @@ -#pragma once +/** + * @file temperature.hpp + * @brief Initialize temperature + */ -#ifndef __temperature_H__ -#define __temperature_H__ +#ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ +#define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ #include @@ -31,11 +34,12 @@ class Temperature : public ILoggable { Temperature(); virtual ~Temperature(); void Propagate(Vector<3> sun_direction, - const double endtime); //太陽入熱量計算のため, 太陽方向の情報を入手 + const double endtime); // 太陽入熱量計算のため, 太陽方向の情報を入手 std::vector GetVnodes() const; void AddHeaterPower(std::vector heater_power); std::string GetLogHeader() const; std::string GetLogValue() const; - void PrintParams(void); //デバッグ出力 + void PrintParams(void); // デバッグ出力 }; -#endif //__temperature_H__ + +#endif // S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ From a2fe8389353fae359e751a2ca9b5ca4d36f5804c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:48:48 +0100 Subject: [PATCH 0252/1086] Rename Interface directory --- CMakeLists.txt | 10 +++++----- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Component/AOCS/Gyro.h | 2 +- src/Component/AOCS/InitGnssReceiver.cpp | 2 +- src/Component/AOCS/InitGyro.cpp | 2 +- src/Component/AOCS/InitMagSensor.cpp | 2 +- src/Component/AOCS/InitMagTorquer.cpp | 2 +- src/Component/AOCS/InitRwModel.cpp | 2 +- src/Component/AOCS/InitStt.cpp | 2 +- src/Component/AOCS/InitSunSensor.cpp | 2 +- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.cpp | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/RWModel.h | 4 ++-- src/Component/AOCS/STT.cpp | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/AOCS/SunSensor.cpp | 2 +- src/Component/AOCS/SunSensor.h | 2 +- src/Component/Abstract/ComponentBase.h | 2 +- .../Abstract/I2cControllerCommunicationBase.h | 2 +- src/Component/Abstract/InitializeSensorBase_tfs.hpp | 2 +- src/Component/Abstract/ObcCommunicationBase.h | 2 +- src/Component/Abstract/ObcI2cTargetCommunicationBase.h | 2 +- src/Component/CDH/OBC.h | 6 +++--- src/Component/CDH/OBC_C2A.h | 2 +- src/Component/CommGS/AntennaRadiationPattern.cpp | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/CommGS/InitAntenna.cpp | 2 +- src/Component/CommGS/InitGsCalculator.cpp | 2 +- src/Component/IdealComponents/ForceGenerator.hpp | 2 +- .../IdealComponents/InitializeForceGenerator.cpp | 2 +- .../IdealComponents/InitializeTorqueGenerator.cpp | 2 +- src/Component/IdealComponents/TorqueGenerator.hpp | 2 +- src/Component/Mission/Telescope/InitTelescope.cpp | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/Component/Power/BAT.h | 2 +- src/Component/Power/CsvScenarioInterface.cpp | 2 +- src/Component/Power/InitBat.cpp | 2 +- src/Component/Power/InitPcu_InitialStudy.cpp | 2 +- src/Component/Power/InitSap.cpp | 2 +- src/Component/Power/PCU.h | 4 ++-- src/Component/Power/PCU_InitialStudy.h | 2 +- src/Component/Power/SAP.h | 2 +- src/Component/Propulsion/InitSimpleThruster.cpp | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- src/Component/examples/example_change_structure.hpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- .../solar_radiation_pressure_disturbance.cpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/attitude/initialize_attitude.cpp | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/dynamics/thermal/initialize_node.cpp | 2 +- src/dynamics/thermal/initialize_temperature.cpp | 2 +- src/dynamics/thermal/node.hpp | 2 +- src/dynamics/thermal/temperature.hpp | 2 +- src/environment/global/celestial_information.cpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/global_environment.cpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- .../global/initialize_global_environment.cpp | 2 +- src/environment/global/initialize_gnss_satellites.cpp | 2 +- src/environment/global/simulation_time.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- src/environment/local/initialize_local_environment.cpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/{Interface => interface}/HilsInOut/CMakeLists.txt | 0 .../HilsInOut/ComPortInterface.cpp | 0 .../HilsInOut/ComPortInterface.h | 0 .../HilsInOut/HardwareMessage.cpp | 0 .../HilsInOut/HardwareMessage.h | 0 .../HilsInOut/HilsPortManager.cpp | 0 .../HilsInOut/HilsPortManager.h | 0 .../HilsInOut/InitCosmosWrapper.cpp | 0 .../HilsInOut/InitHardwareMessage.cpp | 0 .../HilsInOut/Ports/HilsI2cTargetPort.cpp | 0 .../HilsInOut/Ports/HilsI2cTargetPort.h | 0 .../HilsInOut/Ports/HilsUartPort.cpp | 0 .../HilsInOut/Ports/HilsUartPort.h | 0 src/{Interface => interface}/InitInput/CMakeLists.txt | 0 src/{Interface => interface}/InitInput/IniAccess.cpp | 0 src/{Interface => interface}/InitInput/IniAccess.h | 0 src/{Interface => interface}/LogOutput/CMakeLists.txt | 0 src/{Interface => interface}/LogOutput/ILoggable.h | 0 src/{Interface => interface}/LogOutput/InitLog.cpp | 2 +- src/{Interface => interface}/LogOutput/InitLog.hpp | 2 +- src/{Interface => interface}/LogOutput/LogUtility.h | 0 src/{Interface => interface}/LogOutput/Logger.cpp | 0 src/{Interface => interface}/LogOutput/Logger.h | 0 .../SpacecraftInOut/CMakeLists.txt | 0 .../SpacecraftInOut/Ports/GPIOPort.cpp | 0 .../SpacecraftInOut/Ports/GPIOPort.h | 0 .../SpacecraftInOut/Ports/I2CPort.cpp | 0 .../SpacecraftInOut/Ports/I2CPort.h | 0 .../SpacecraftInOut/Ports/PowerPort.cpp | 2 +- .../SpacecraftInOut/Ports/PowerPort.h | 0 .../SpacecraftInOut/Ports/SCIPort.cpp | 0 .../SpacecraftInOut/Ports/SCIPort.h | 0 .../SpacecraftInOut/Utils/ITCTMChannel.h | 0 .../SpacecraftInOut/Utils/RingBuffer.cpp | 0 .../SpacecraftInOut/Utils/RingBuffer.h | 0 src/relative_information/relative_information.hpp | 4 ++-- src/s2e.cpp | 6 +++--- src/simulation/case/simulation_case.cpp | 4 ++-- src/simulation/case/simulation_case.hpp | 2 +- src/simulation/ground_station/ground_station.cpp | 6 +++--- .../sample_ground_station_components.cpp | 2 +- .../initialize_monte_carlo_simulation.cpp | 2 +- src/simulation/simulation_configuration.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- .../spacecraft/structure/initialize_structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.cpp | 2 +- 139 files changed, 122 insertions(+), 122 deletions(-) rename src/{Interface => interface}/HilsInOut/CMakeLists.txt (100%) rename src/{Interface => interface}/HilsInOut/ComPortInterface.cpp (100%) rename src/{Interface => interface}/HilsInOut/ComPortInterface.h (100%) rename src/{Interface => interface}/HilsInOut/HardwareMessage.cpp (100%) rename src/{Interface => interface}/HilsInOut/HardwareMessage.h (100%) rename src/{Interface => interface}/HilsInOut/HilsPortManager.cpp (100%) rename src/{Interface => interface}/HilsInOut/HilsPortManager.h (100%) rename src/{Interface => interface}/HilsInOut/InitCosmosWrapper.cpp (100%) rename src/{Interface => interface}/HilsInOut/InitHardwareMessage.cpp (100%) rename src/{Interface => interface}/HilsInOut/Ports/HilsI2cTargetPort.cpp (100%) rename src/{Interface => interface}/HilsInOut/Ports/HilsI2cTargetPort.h (100%) rename src/{Interface => interface}/HilsInOut/Ports/HilsUartPort.cpp (100%) rename src/{Interface => interface}/HilsInOut/Ports/HilsUartPort.h (100%) rename src/{Interface => interface}/InitInput/CMakeLists.txt (100%) rename src/{Interface => interface}/InitInput/IniAccess.cpp (100%) rename src/{Interface => interface}/InitInput/IniAccess.h (100%) rename src/{Interface => interface}/LogOutput/CMakeLists.txt (100%) rename src/{Interface => interface}/LogOutput/ILoggable.h (100%) rename src/{Interface => interface}/LogOutput/InitLog.cpp (95%) rename src/{Interface => interface}/LogOutput/InitLog.hpp (92%) rename src/{Interface => interface}/LogOutput/LogUtility.h (100%) rename src/{Interface => interface}/LogOutput/Logger.cpp (100%) rename src/{Interface => interface}/LogOutput/Logger.h (100%) rename src/{Interface => interface}/SpacecraftInOut/CMakeLists.txt (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/GPIOPort.cpp (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/GPIOPort.h (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/I2CPort.cpp (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/I2CPort.h (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/PowerPort.cpp (98%) rename src/{Interface => interface}/SpacecraftInOut/Ports/PowerPort.h (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/SCIPort.cpp (100%) rename src/{Interface => interface}/SpacecraftInOut/Ports/SCIPort.h (100%) rename src/{Interface => interface}/SpacecraftInOut/Utils/ITCTMChannel.h (100%) rename src/{Interface => interface}/SpacecraftInOut/Utils/RingBuffer.cpp (100%) rename src/{Interface => interface}/SpacecraftInOut/Utils/RingBuffer.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index afc07a906..a60fcfd87 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,7 +41,7 @@ if(USE_C2A) add_definitions(-DSILS_FW) #include_directories include_directories(${C2A_DIR}/src) - include_directories(${S2E_CORE_DIR}/src/Interface/SpacecraftInOut) + include_directories(${S2E_CORE_DIR}/src/interface/SpacecraftInOut) #add subdirectory add_subdirectory(${C2A_DIR} C2A) endif() @@ -70,10 +70,10 @@ add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/Component) add_subdirectory(src/relative_information) -add_subdirectory(src/Interface/InitInput) -add_subdirectory(src/Interface/LogOutput) -add_subdirectory(src/Interface/SpacecraftInOut) -add_subdirectory(src/Interface/HilsInOut) +add_subdirectory(src/interface/InitInput) +add_subdirectory(src/interface/LogOutput) +add_subdirectory(src/interface/SpacecraftInOut) +add_subdirectory(src/interface/HilsInOut) add_subdirectory(src/Library/igrf) add_subdirectory(src/Library/inih) add_subdirectory(src/Library/math) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 8042c96aa..8722ca7e6 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -5,7 +5,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/AOCS/Gyro.h b/src/Component/AOCS/Gyro.h index 1572a326e..5debea2ff 100644 --- a/src/Component/AOCS/Gyro.h +++ b/src/Component/AOCS/Gyro.h @@ -6,7 +6,7 @@ #ifndef Gyro_H_ #define Gyro_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index 89f46de88..e721a5f62 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -6,7 +6,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" typedef struct _gnssrecever_param { int prescaler; diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 0590c6c4a..e7b6f815a 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -4,7 +4,7 @@ */ #include "InitGyro.hpp" -#include +#include #include "../Abstract/InitializeSensorBase.hpp" diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index ae3e780ef..db2be7fdc 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -5,7 +5,7 @@ #include "InitMagSensor.hpp" #include "../Abstract/InitializeSensorBase.hpp" -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index 05cf48a7d..823c1cc53 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -4,7 +4,7 @@ */ #include "InitMagTorquer.hpp" -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index fdad97695..f1bebe86e 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -6,7 +6,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" // In order to share processing among initialization functions, variables should also be shared. These variables have internal linkages and cannot be // referenced from the outside. diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index e123ab1fa..176ab96e1 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -6,7 +6,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" using namespace std; diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index c8a750b21..02aecad7f 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -8,7 +8,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index 89842e7ac..e564ec4b1 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,7 +6,7 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/Component/AOCS/MagTorquer.cpp index e9576775e..10de9f6fa 100644 --- a/src/Component/AOCS/MagTorquer.cpp +++ b/src/Component/AOCS/MagTorquer.cpp @@ -5,7 +5,7 @@ #include "MagTorquer.h" -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index 9cf7de1b6..5ec790cea 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,7 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index 18f0ffc21..dc01736c2 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -5,8 +5,8 @@ #ifndef __RWModel_H__ #define __RWModel_H__ -#include -#include +#include +#include #include #include diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index 76f8a1d4e..1d55a9899 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -5,7 +5,7 @@ #include "STT.h" -#include +#include #include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index e9e84aa1a..ccc6785f1 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -8,7 +8,7 @@ #ifndef __STT_H__ #define __STT_H__ -#include +#include #include #include diff --git a/src/Component/AOCS/SunSensor.cpp b/src/Component/AOCS/SunSensor.cpp index 0b6602267..9c6ab3590 100644 --- a/src/Component/AOCS/SunSensor.cpp +++ b/src/Component/AOCS/SunSensor.cpp @@ -8,7 +8,7 @@ #include #include using libra::NormalRand; -#include +#include #include using namespace std; diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index 5eb9cca3d..5c5df07e8 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,7 +6,7 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include +#include #include #include diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 96fd99fe3..8a8555b6e 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Abstract/I2cControllerCommunicationBase.h b/src/Component/Abstract/I2cControllerCommunicationBase.h index 6ac901798..e9671f0c7 100644 --- a/src/Component/Abstract/I2cControllerCommunicationBase.h +++ b/src/Component/Abstract/I2cControllerCommunicationBase.h @@ -3,7 +3,7 @@ * @brief This class simulates the I2C Controller communication with the I2C Target. */ #pragma once -#include "../../Interface/HilsInOut/HilsPortManager.h" +#include "../../interface/HilsInOut/HilsPortManager.h" #include "ObcCommunicationBase.h" /** diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index 9e7057892..a6a80183a 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, diff --git a/src/Component/Abstract/ObcCommunicationBase.h b/src/Component/Abstract/ObcCommunicationBase.h index 20e3b4e2e..d0a23045a 100644 --- a/src/Component/Abstract/ObcCommunicationBase.h +++ b/src/Component/Abstract/ObcCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for serial communication (e.g., UART) with OBC flight software */ #pragma once -#include +#include #include "../CDH/OBC.h" diff --git a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h index 11b16e004..36133579a 100644 --- a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h +++ b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for I2C communication as target side with OBC flight software */ #pragma once -#include "../../Interface/HilsInOut/HilsPortManager.h" +#include "../../interface/HilsInOut/HilsPortManager.h" #include "../CDH/OBC.h" #include "ObcCommunicationBase.h" diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index d1001c84f..6e0b3f801 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -3,9 +3,9 @@ * @brief Class to emulate on board computer */ #pragma once -#include -#include -#include +#include +#include +#include #include diff --git a/src/Component/CDH/OBC_C2A.h b/src/Component/CDH/OBC_C2A.h index 62b9819b2..21efaa49d 100644 --- a/src/Component/CDH/OBC_C2A.h +++ b/src/Component/CDH/OBC_C2A.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include "OBC.h" diff --git a/src/Component/CommGS/AntennaRadiationPattern.cpp b/src/Component/CommGS/AntennaRadiationPattern.cpp index 7f7eaae0a..7fa3c2d6e 100644 --- a/src/Component/CommGS/AntennaRadiationPattern.cpp +++ b/src/Component/CommGS/AntennaRadiationPattern.cpp @@ -5,7 +5,7 @@ #include "AntennaRadiationPattern.hpp" -#include +#include #include #include diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 8110d0547..122a0e837 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,7 +6,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/Component/CommGS/InitAntenna.cpp index 889b58172..af8d11f5d 100644 --- a/src/Component/CommGS/InitAntenna.cpp +++ b/src/Component/CommGS/InitAntenna.cpp @@ -10,7 +10,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" using libra::Vector; diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/Component/CommGS/InitGsCalculator.cpp index 8b741aad3..52f3bfa0a 100644 --- a/src/Component/CommGS/InitGsCalculator.cpp +++ b/src/Component/CommGS/InitGsCalculator.cpp @@ -8,7 +8,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" GScalculator InitGScalculator(const std::string fname) { IniAccess gs_conf(fname); diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/Component/IdealComponents/ForceGenerator.hpp index 28537de49..6b15a7556 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/Component/IdealComponents/ForceGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/IdealComponents/InitializeForceGenerator.cpp b/src/Component/IdealComponents/InitializeForceGenerator.cpp index e7acb3d13..6af6a3fab 100644 --- a/src/Component/IdealComponents/InitializeForceGenerator.cpp +++ b/src/Component/IdealComponents/InitializeForceGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeForceGenerator.hpp" -#include +#include ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp index a64745eb1..4b4e2ca3d 100644 --- a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp +++ b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeTorqueGenerator.hpp" -#include +#include TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/Component/IdealComponents/TorqueGenerator.hpp index 581a4d17f..2db0aea33 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/Component/IdealComponents/TorqueGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index 0d3838ffb..e08759a28 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -9,7 +9,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" using namespace std; diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index 6a28f7988..fcae00831 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Power/BAT.h b/src/Component/Power/BAT.h index 346fea9cc..b5dda9648 100644 --- a/src/Component/Power/BAT.h +++ b/src/Component/Power/BAT.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/CsvScenarioInterface.cpp b/src/Component/Power/CsvScenarioInterface.cpp index a71c1f899..8a4872c65 100644 --- a/src/Component/Power/CsvScenarioInterface.cpp +++ b/src/Component/Power/CsvScenarioInterface.cpp @@ -5,7 +5,7 @@ #include "CsvScenarioInterface.h" -#include +#include bool CsvScenarioInterface::is_csv_senario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; diff --git a/src/Component/Power/InitBat.cpp b/src/Component/Power/InitBat.cpp index 1ff27402b..96ff475d5 100644 --- a/src/Component/Power/InitBat.cpp +++ b/src/Component/Power/InitBat.cpp @@ -8,7 +8,7 @@ #include #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time) { IniAccess bat_conf(fname); diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/Component/Power/InitPcu_InitialStudy.cpp index f8fc17a4a..034e3cbfa 100644 --- a/src/Component/Power/InitPcu_InitialStudy.cpp +++ b/src/Component/Power/InitPcu_InitialStudy.cpp @@ -9,7 +9,7 @@ #include #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time) { diff --git a/src/Component/Power/InitSap.cpp b/src/Component/Power/InitSap.cpp index 6bdb6fd6e..66233527a 100644 --- a/src/Component/Power/InitSap.cpp +++ b/src/Component/Power/InitSap.cpp @@ -7,7 +7,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index f1f3049a9..c00e932ed 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -4,8 +4,8 @@ */ #pragma once -#include -#include +#include +#include #include diff --git a/src/Component/Power/PCU_InitialStudy.h b/src/Component/Power/PCU_InitialStudy.h index 5f43ba351..cfc7b2483 100644 --- a/src/Component/Power/PCU_InitialStudy.h +++ b/src/Component/Power/PCU_InitialStudy.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index e739ceed4..6fc673108 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 84fe9d3dd..24868df17 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -6,7 +6,7 @@ #include -#include "Interface/InitInput/IniAccess.h" +#include "interface/InitInput/IniAccess.h" SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 6c19966c9..2f3cd6425 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 278e65cbd..70e82cdb7 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index ed93060e4..ed9f3e3c9 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -10,7 +10,7 @@ #include #include -#include "../Interface/LogOutput/LogUtility.h" +#include "../interface/LogOutput/LogUtility.h" using namespace std; using namespace libra; diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 998fb1039..310c420cb 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 14077bdd9..5d51bf77f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -5,7 +5,7 @@ #include "disturbances.hpp" -#include +#include #include "air_drag.hpp" #include "geopotential.hpp" diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 5ee48c094..c899fbf16 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -11,7 +11,7 @@ #include #include -#include "../Interface/LogOutput/LogUtility.h" +#include "../interface/LogOutput/LogUtility.h" // #define DEBUG_GEOPOTENTIAL diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 44d97f97a..147d578dc 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,7 +8,7 @@ #include -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index ef58c658d..d18027667 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -10,7 +10,7 @@ #include #include -#include "../Interface/LogOutput/LogUtility.h" +#include "../interface/LogOutput/LogUtility.h" using namespace std; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 59f76fe80..58a07d407 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,7 +8,7 @@ #include -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 193564baa..b7ef429fc 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -5,7 +5,7 @@ #include "initialize_disturbances.hpp" -#include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 267dbf34d..8b2e0c29c 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,7 +9,7 @@ using libra::NormalRand; #include -#include "../Interface/LogOutput/LogUtility.h" +#include "../interface/LogOutput/LogUtility.h" #include "../Library/math/GlobalRand.h" #include "../Library/math/RandomWalk.hpp" diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index a5a99819a..391b39a68 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -11,7 +11,7 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 26fe3ff29..713075ef6 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -7,7 +7,7 @@ #include -#include "../Interface/LogOutput/LogUtility.h" +#include "../interface/LogOutput/LogUtility.h" SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b) : SurfaceForce(surfaces, cg_b) {} diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 562b03657..6cce14c69 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,7 +9,7 @@ #include #include -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../Library/math/Vector.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index fb4a3afee..b2fb1b4cb 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../Interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/ILoggable.h" #include "../Library/math/Vector.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index b42ad2984..b985fea74 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -4,7 +4,7 @@ */ #include "attitude.hpp" -#include +#include Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { omega_b_rad_s_ = libra::Vector<3>(0.0); diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index d1f4e87fb..7ffded924 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include +#include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 67e7f7ac1..bbbc23eda 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 84c2273eb..c66b76c35 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,7 +4,7 @@ */ #include "controlled_attitude.hpp" -#include +#include #include #include diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 5e0a9b2c1..748da2c3f 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -4,7 +4,7 @@ */ #include "initialize_attitude.hpp" -#include +#include Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id) { diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index ca9ae4d80..5766791ca 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -4,7 +4,7 @@ */ #include "initialize_orbit.hpp" -#include +#include #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 2536ddf29..d2153ea1c 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,7 +16,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index 6410298f9..81d5bdbb9 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -5,7 +5,7 @@ #include "initialize_node.hpp" -#include +#include #include #include diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 89d9dd9b0..6cf468cfe 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -5,7 +5,7 @@ #include "initialize_temperature.hpp" -#include +#include #include #include diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index b9c4b4ba1..71d8d8bcc 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_NODE_H_ #define S2E_DYNAMICS_THERMAL_NODE_H_ -#include +#include #include #include diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 44fd33fbf..c2437b77c 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ #define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ -#include +#include #include #include diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 575929d7e..de3733d8e 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -6,7 +6,7 @@ #include "celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 7306de4e9..eb2bd2a80 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,7 +10,7 @@ #include #include -#include "Interface/LogOutput/ILoggable.h" +#include "interface/LogOutput/ILoggable.h" #include "Library/math/MatVec.hpp" #include "Library/math/Matrix.hpp" #include "Library/math/Quaternion.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 7177141c3..ad0356572 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,7 +10,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include +#include #include #include diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 8816eda28..8a9a2278a 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -5,7 +5,7 @@ #include "global_environment.hpp" -#include +#include #include "initialize_global_environment.hpp" #include "initialize_gnss_satellites.hpp" diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index ff7eeaea8..67e55673b 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ -#include +#include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 4f3d60173..9492f5428 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "gnss_satellites.hpp" -#include +#include #include //for jday() #include //for gstime() diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index f24a1169e..8930b0a0a 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include +#include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 08c3c4f44..2349b19af 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include +#include #include #include diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 529ac5ef0..6a0fc4621 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -4,7 +4,7 @@ */ #include "initialize_global_environment.hpp" -#include +#include #include #include diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index ffdb3643b..c223e6838 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "initialize_gnss_satellites.hpp" -#include +#include #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 9ef27fe74..5d9dfb151 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,7 +12,7 @@ #include // #include -#include +#include #include #include #include diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index e90ce32bc..07b6a908d 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,7 +5,7 @@ #include "atmosphere.hpp" -#include +#include #include #include diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 52d9de7f7..8feb4112a 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,7 +7,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 59dad1928..ca1283fd3 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,7 +5,7 @@ #include "geomagnetic_field.hpp" -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index ccadd183e..7883298fe 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -11,7 +11,7 @@ using libra::Vector; #include using libra::Quaternion; -#include +#include /** * @class MagEnvironment diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 841f895c7..9cf037ec6 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -5,7 +5,7 @@ #include "initialize_local_environment.hpp" -#include +#include #include diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 375b0b928..18f0b6180 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -5,7 +5,7 @@ #include "local_celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 5747b4cca..a5edb08fe 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,7 +4,7 @@ */ #include "local_environment.hpp" -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 87f241039..ccf26e439 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,7 +4,7 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 841e9ebbe..543177846 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/Interface/HilsInOut/CMakeLists.txt b/src/interface/HilsInOut/CMakeLists.txt similarity index 100% rename from src/Interface/HilsInOut/CMakeLists.txt rename to src/interface/HilsInOut/CMakeLists.txt diff --git a/src/Interface/HilsInOut/ComPortInterface.cpp b/src/interface/HilsInOut/ComPortInterface.cpp similarity index 100% rename from src/Interface/HilsInOut/ComPortInterface.cpp rename to src/interface/HilsInOut/ComPortInterface.cpp diff --git a/src/Interface/HilsInOut/ComPortInterface.h b/src/interface/HilsInOut/ComPortInterface.h similarity index 100% rename from src/Interface/HilsInOut/ComPortInterface.h rename to src/interface/HilsInOut/ComPortInterface.h diff --git a/src/Interface/HilsInOut/HardwareMessage.cpp b/src/interface/HilsInOut/HardwareMessage.cpp similarity index 100% rename from src/Interface/HilsInOut/HardwareMessage.cpp rename to src/interface/HilsInOut/HardwareMessage.cpp diff --git a/src/Interface/HilsInOut/HardwareMessage.h b/src/interface/HilsInOut/HardwareMessage.h similarity index 100% rename from src/Interface/HilsInOut/HardwareMessage.h rename to src/interface/HilsInOut/HardwareMessage.h diff --git a/src/Interface/HilsInOut/HilsPortManager.cpp b/src/interface/HilsInOut/HilsPortManager.cpp similarity index 100% rename from src/Interface/HilsInOut/HilsPortManager.cpp rename to src/interface/HilsInOut/HilsPortManager.cpp diff --git a/src/Interface/HilsInOut/HilsPortManager.h b/src/interface/HilsInOut/HilsPortManager.h similarity index 100% rename from src/Interface/HilsInOut/HilsPortManager.h rename to src/interface/HilsInOut/HilsPortManager.h diff --git a/src/Interface/HilsInOut/InitCosmosWrapper.cpp b/src/interface/HilsInOut/InitCosmosWrapper.cpp similarity index 100% rename from src/Interface/HilsInOut/InitCosmosWrapper.cpp rename to src/interface/HilsInOut/InitCosmosWrapper.cpp diff --git a/src/Interface/HilsInOut/InitHardwareMessage.cpp b/src/interface/HilsInOut/InitHardwareMessage.cpp similarity index 100% rename from src/Interface/HilsInOut/InitHardwareMessage.cpp rename to src/interface/HilsInOut/InitHardwareMessage.cpp diff --git a/src/Interface/HilsInOut/Ports/HilsI2cTargetPort.cpp b/src/interface/HilsInOut/Ports/HilsI2cTargetPort.cpp similarity index 100% rename from src/Interface/HilsInOut/Ports/HilsI2cTargetPort.cpp rename to src/interface/HilsInOut/Ports/HilsI2cTargetPort.cpp diff --git a/src/Interface/HilsInOut/Ports/HilsI2cTargetPort.h b/src/interface/HilsInOut/Ports/HilsI2cTargetPort.h similarity index 100% rename from src/Interface/HilsInOut/Ports/HilsI2cTargetPort.h rename to src/interface/HilsInOut/Ports/HilsI2cTargetPort.h diff --git a/src/Interface/HilsInOut/Ports/HilsUartPort.cpp b/src/interface/HilsInOut/Ports/HilsUartPort.cpp similarity index 100% rename from src/Interface/HilsInOut/Ports/HilsUartPort.cpp rename to src/interface/HilsInOut/Ports/HilsUartPort.cpp diff --git a/src/Interface/HilsInOut/Ports/HilsUartPort.h b/src/interface/HilsInOut/Ports/HilsUartPort.h similarity index 100% rename from src/Interface/HilsInOut/Ports/HilsUartPort.h rename to src/interface/HilsInOut/Ports/HilsUartPort.h diff --git a/src/Interface/InitInput/CMakeLists.txt b/src/interface/InitInput/CMakeLists.txt similarity index 100% rename from src/Interface/InitInput/CMakeLists.txt rename to src/interface/InitInput/CMakeLists.txt diff --git a/src/Interface/InitInput/IniAccess.cpp b/src/interface/InitInput/IniAccess.cpp similarity index 100% rename from src/Interface/InitInput/IniAccess.cpp rename to src/interface/InitInput/IniAccess.cpp diff --git a/src/Interface/InitInput/IniAccess.h b/src/interface/InitInput/IniAccess.h similarity index 100% rename from src/Interface/InitInput/IniAccess.h rename to src/interface/InitInput/IniAccess.h diff --git a/src/Interface/LogOutput/CMakeLists.txt b/src/interface/LogOutput/CMakeLists.txt similarity index 100% rename from src/Interface/LogOutput/CMakeLists.txt rename to src/interface/LogOutput/CMakeLists.txt diff --git a/src/Interface/LogOutput/ILoggable.h b/src/interface/LogOutput/ILoggable.h similarity index 100% rename from src/Interface/LogOutput/ILoggable.h rename to src/interface/LogOutput/ILoggable.h diff --git a/src/Interface/LogOutput/InitLog.cpp b/src/interface/LogOutput/InitLog.cpp similarity index 95% rename from src/Interface/LogOutput/InitLog.cpp rename to src/interface/LogOutput/InitLog.cpp index e4cd82e03..1ab6310ad 100644 --- a/src/Interface/LogOutput/InitLog.cpp +++ b/src/interface/LogOutput/InitLog.cpp @@ -5,7 +5,7 @@ #include "InitLog.hpp" -#include +#include Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); diff --git a/src/Interface/LogOutput/InitLog.hpp b/src/interface/LogOutput/InitLog.hpp similarity index 92% rename from src/Interface/LogOutput/InitLog.hpp rename to src/interface/LogOutput/InitLog.hpp index 1a52219c6..a1dadfab0 100644 --- a/src/Interface/LogOutput/InitLog.hpp +++ b/src/interface/LogOutput/InitLog.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitLog diff --git a/src/Interface/LogOutput/LogUtility.h b/src/interface/LogOutput/LogUtility.h similarity index 100% rename from src/Interface/LogOutput/LogUtility.h rename to src/interface/LogOutput/LogUtility.h diff --git a/src/Interface/LogOutput/Logger.cpp b/src/interface/LogOutput/Logger.cpp similarity index 100% rename from src/Interface/LogOutput/Logger.cpp rename to src/interface/LogOutput/Logger.cpp diff --git a/src/Interface/LogOutput/Logger.h b/src/interface/LogOutput/Logger.h similarity index 100% rename from src/Interface/LogOutput/Logger.h rename to src/interface/LogOutput/Logger.h diff --git a/src/Interface/SpacecraftInOut/CMakeLists.txt b/src/interface/SpacecraftInOut/CMakeLists.txt similarity index 100% rename from src/Interface/SpacecraftInOut/CMakeLists.txt rename to src/interface/SpacecraftInOut/CMakeLists.txt diff --git a/src/Interface/SpacecraftInOut/Ports/GPIOPort.cpp b/src/interface/SpacecraftInOut/Ports/GPIOPort.cpp similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/GPIOPort.cpp rename to src/interface/SpacecraftInOut/Ports/GPIOPort.cpp diff --git a/src/Interface/SpacecraftInOut/Ports/GPIOPort.h b/src/interface/SpacecraftInOut/Ports/GPIOPort.h similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/GPIOPort.h rename to src/interface/SpacecraftInOut/Ports/GPIOPort.h diff --git a/src/Interface/SpacecraftInOut/Ports/I2CPort.cpp b/src/interface/SpacecraftInOut/Ports/I2CPort.cpp similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/I2CPort.cpp rename to src/interface/SpacecraftInOut/Ports/I2CPort.cpp diff --git a/src/Interface/SpacecraftInOut/Ports/I2CPort.h b/src/interface/SpacecraftInOut/Ports/I2CPort.h similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/I2CPort.h rename to src/interface/SpacecraftInOut/Ports/I2CPort.h diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp similarity index 98% rename from src/Interface/SpacecraftInOut/Ports/PowerPort.cpp rename to src/interface/SpacecraftInOut/Ports/PowerPort.cpp index 4f1c37f78..6546291fe 100644 --- a/src/Interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -5,7 +5,7 @@ #include "PowerPort.h" -#include +#include #include diff --git a/src/Interface/SpacecraftInOut/Ports/PowerPort.h b/src/interface/SpacecraftInOut/Ports/PowerPort.h similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/PowerPort.h rename to src/interface/SpacecraftInOut/Ports/PowerPort.h diff --git a/src/Interface/SpacecraftInOut/Ports/SCIPort.cpp b/src/interface/SpacecraftInOut/Ports/SCIPort.cpp similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/SCIPort.cpp rename to src/interface/SpacecraftInOut/Ports/SCIPort.cpp diff --git a/src/Interface/SpacecraftInOut/Ports/SCIPort.h b/src/interface/SpacecraftInOut/Ports/SCIPort.h similarity index 100% rename from src/Interface/SpacecraftInOut/Ports/SCIPort.h rename to src/interface/SpacecraftInOut/Ports/SCIPort.h diff --git a/src/Interface/SpacecraftInOut/Utils/ITCTMChannel.h b/src/interface/SpacecraftInOut/Utils/ITCTMChannel.h similarity index 100% rename from src/Interface/SpacecraftInOut/Utils/ITCTMChannel.h rename to src/interface/SpacecraftInOut/Utils/ITCTMChannel.h diff --git a/src/Interface/SpacecraftInOut/Utils/RingBuffer.cpp b/src/interface/SpacecraftInOut/Utils/RingBuffer.cpp similarity index 100% rename from src/Interface/SpacecraftInOut/Utils/RingBuffer.cpp rename to src/interface/SpacecraftInOut/Utils/RingBuffer.cpp diff --git a/src/Interface/SpacecraftInOut/Utils/RingBuffer.h b/src/interface/SpacecraftInOut/Utils/RingBuffer.h similarity index 100% rename from src/Interface/SpacecraftInOut/Utils/RingBuffer.h rename to src/interface/SpacecraftInOut/Utils/RingBuffer.h diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 0a332a9a4..890219979 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -9,8 +9,8 @@ #include #include "../dynamics/dynamics.hpp" -#include "../Interface/LogOutput/ILoggable.h" -#include "../Interface/LogOutput/Logger.h" +#include "../interface/LogOutput/ILoggable.h" +#include "../interface/LogOutput/Logger.h" /** * @class RelativeInformation diff --git a/src/s2e.cpp b/src/s2e.cpp index 289fbc60b..f40432400 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -15,13 +15,13 @@ #include // Simulator includes -#include "Interface/LogOutput/Logger.h" +#include "interface/LogOutput/Logger.h" // Add custom include files #include "simulation/case/sample_case.hpp" // #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" -// #include "Interface/HilsInOut/COSMOSWrapper.h" -// #include "Interface/HilsInOut/HardwareMessage.h" +// #include "interface/HilsInOut/COSMOSWrapper.h" +// #include "interface/HilsInOut/HardwareMessage.h" void print_path(std::string path) { #ifdef WIN32 diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index df65ee9c4..ab7515498 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -5,9 +5,9 @@ #include "simulation_case.hpp" -#include +#include -#include +#include #include SimulationCase::SimulationCase(std::string ini_base) { diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index d097402e6..45b294aaa 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include +#include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 9c3d9430d..07396c013 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,9 +5,9 @@ #include "ground_station.hpp" -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 00f52406a..91d7b2350 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -4,7 +4,7 @@ */ #include "sample_ground_station_components.hpp" -#include +#include SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 4538d170d..2f6f735cc 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -5,7 +5,7 @@ #include "initialize_monte_carlo_simulation.hpp" -#include +#include #include diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index 38151233c..09d1a6272 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -9,7 +9,7 @@ #include #include -#include "../Interface/LogOutput/Logger.h" +#include "../interface/LogOutput/Logger.h" /** * @struct SimulationConfig diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index b58a5d46d..284aa46b0 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include +#include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 8a7c2ebc6..2706ca33e 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -5,7 +5,7 @@ #include "sample_components.hpp" -#include +#include #include "sample_port_configuration.hpp" diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index e224fdb68..8607d6163 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 697ac8212..d33a15e89 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -5,8 +5,8 @@ #include "spacecraft.hpp" -#include -#include +#include +#include Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { Initialize(sim_config, glo_env, sat_id); diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 5f0d9fa50..94e40793f 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index c5f2acf5f..5ba0252ea 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -5,7 +5,7 @@ #include "structure.hpp" -#include +#include #include From aee820541f0faa46391b8d06ff7dc43459563e2f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 20:58:48 +0100 Subject: [PATCH 0253/1086] Rename InitInput --- CMakeLists.txt | 2 +- src/Component/AOCS/InitGnssReceiver.cpp | 2 +- src/Component/AOCS/InitGyro.cpp | 2 +- src/Component/AOCS/InitMagSensor.cpp | 2 +- src/Component/AOCS/InitMagTorquer.cpp | 2 +- src/Component/AOCS/InitRwModel.cpp | 2 +- src/Component/AOCS/InitStt.cpp | 2 +- src/Component/AOCS/InitSunSensor.cpp | 2 +- src/Component/Abstract/InitializeSensorBase_tfs.hpp | 2 +- src/Component/CommGS/AntennaRadiationPattern.cpp | 2 +- src/Component/CommGS/InitAntenna.cpp | 2 +- src/Component/CommGS/InitGsCalculator.cpp | 2 +- src/Component/IdealComponents/InitializeForceGenerator.cpp | 2 +- src/Component/IdealComponents/InitializeTorqueGenerator.cpp | 2 +- src/Component/Mission/Telescope/InitTelescope.cpp | 2 +- src/Component/Power/CsvScenarioInterface.cpp | 2 +- src/Component/Power/InitBat.cpp | 2 +- src/Component/Power/InitPcu_InitialStudy.cpp | 2 +- src/Component/Power/InitSap.cpp | 2 +- src/Component/Propulsion/InitSimpleThruster.cpp | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- src/dynamics/attitude/initialize_attitude.cpp | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/thermal/initialize_node.cpp | 2 +- src/dynamics/thermal/initialize_temperature.cpp | 2 +- src/environment/global/global_environment.cpp | 2 +- src/environment/global/initialize_global_environment.cpp | 2 +- src/environment/global/initialize_gnss_satellites.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/environment/local/initialize_local_environment.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/interface/LogOutput/InitLog.cpp | 2 +- src/interface/SpacecraftInOut/Ports/PowerPort.cpp | 2 +- src/interface/{InitInput => initialize}/CMakeLists.txt | 0 src/interface/{InitInput => initialize}/IniAccess.cpp | 0 src/interface/{InitInput => initialize}/IniAccess.h | 0 src/simulation/case/simulation_case.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- .../sample_ground_station/sample_ground_station_components.cpp | 2 +- .../initialize_monte_carlo_simulation.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- src/simulation/spacecraft/structure/initialize_structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.cpp | 2 +- 44 files changed, 41 insertions(+), 41 deletions(-) rename src/interface/{InitInput => initialize}/CMakeLists.txt (100%) rename src/interface/{InitInput => initialize}/IniAccess.cpp (100%) rename src/interface/{InitInput => initialize}/IniAccess.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index a60fcfd87..fc9b5db04 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,7 +70,7 @@ add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/Component) add_subdirectory(src/relative_information) -add_subdirectory(src/interface/InitInput) +add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/LogOutput) add_subdirectory(src/interface/SpacecraftInOut) add_subdirectory(src/interface/HilsInOut) diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index e721a5f62..c3244d09d 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -6,7 +6,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" typedef struct _gnssrecever_param { int prescaler; diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index e7b6f815a..9c5da1158 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -4,7 +4,7 @@ */ #include "InitGyro.hpp" -#include +#include #include "../Abstract/InitializeSensorBase.hpp" diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index db2be7fdc..25c2c2df9 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -5,7 +5,7 @@ #include "InitMagSensor.hpp" #include "../Abstract/InitializeSensorBase.hpp" -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index 823c1cc53..96a41f775 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -4,7 +4,7 @@ */ #include "InitMagTorquer.hpp" -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index f1bebe86e..094b5136d 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -6,7 +6,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" // In order to share processing among initialization functions, variables should also be shared. These variables have internal linkages and cannot be // referenced from the outside. diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index 176ab96e1..195e8daa1 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -6,7 +6,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" using namespace std; diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index 02aecad7f..f4577c700 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -8,7 +8,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index a6a80183a..a99b9864e 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, diff --git a/src/Component/CommGS/AntennaRadiationPattern.cpp b/src/Component/CommGS/AntennaRadiationPattern.cpp index 7fa3c2d6e..f9957261b 100644 --- a/src/Component/CommGS/AntennaRadiationPattern.cpp +++ b/src/Component/CommGS/AntennaRadiationPattern.cpp @@ -5,7 +5,7 @@ #include "AntennaRadiationPattern.hpp" -#include +#include #include #include diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/Component/CommGS/InitAntenna.cpp index af8d11f5d..4180e8d2f 100644 --- a/src/Component/CommGS/InitAntenna.cpp +++ b/src/Component/CommGS/InitAntenna.cpp @@ -10,7 +10,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" using libra::Vector; diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/Component/CommGS/InitGsCalculator.cpp index 52f3bfa0a..65f952fc7 100644 --- a/src/Component/CommGS/InitGsCalculator.cpp +++ b/src/Component/CommGS/InitGsCalculator.cpp @@ -8,7 +8,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" GScalculator InitGScalculator(const std::string fname) { IniAccess gs_conf(fname); diff --git a/src/Component/IdealComponents/InitializeForceGenerator.cpp b/src/Component/IdealComponents/InitializeForceGenerator.cpp index 6af6a3fab..b776cecc1 100644 --- a/src/Component/IdealComponents/InitializeForceGenerator.cpp +++ b/src/Component/IdealComponents/InitializeForceGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeForceGenerator.hpp" -#include +#include ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp index 4b4e2ca3d..b044d67d9 100644 --- a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp +++ b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeTorqueGenerator.hpp" -#include +#include TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index e08759a28..df5b7e6d1 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -9,7 +9,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" using namespace std; diff --git a/src/Component/Power/CsvScenarioInterface.cpp b/src/Component/Power/CsvScenarioInterface.cpp index 8a4872c65..ba12ed4dc 100644 --- a/src/Component/Power/CsvScenarioInterface.cpp +++ b/src/Component/Power/CsvScenarioInterface.cpp @@ -5,7 +5,7 @@ #include "CsvScenarioInterface.h" -#include +#include bool CsvScenarioInterface::is_csv_senario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; diff --git a/src/Component/Power/InitBat.cpp b/src/Component/Power/InitBat.cpp index 96ff475d5..61d727cb6 100644 --- a/src/Component/Power/InitBat.cpp +++ b/src/Component/Power/InitBat.cpp @@ -8,7 +8,7 @@ #include #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time) { IniAccess bat_conf(fname); diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/Component/Power/InitPcu_InitialStudy.cpp index 034e3cbfa..a09f429de 100644 --- a/src/Component/Power/InitPcu_InitialStudy.cpp +++ b/src/Component/Power/InitPcu_InitialStudy.cpp @@ -9,7 +9,7 @@ #include #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time) { diff --git a/src/Component/Power/InitSap.cpp b/src/Component/Power/InitSap.cpp index 66233527a..435076a8f 100644 --- a/src/Component/Power/InitSap.cpp +++ b/src/Component/Power/InitSap.cpp @@ -7,7 +7,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 24868df17..759cdd0d3 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -6,7 +6,7 @@ #include -#include "interface/InitInput/IniAccess.h" +#include "interface/initialize/IniAccess.h" SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 5d51bf77f..4ae60a8fd 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -5,7 +5,7 @@ #include "disturbances.hpp" -#include +#include #include "air_drag.hpp" #include "geopotential.hpp" diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index b7ef429fc..a215a65ae 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -5,7 +5,7 @@ #include "initialize_disturbances.hpp" -#include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 748da2c3f..616c2fb5d 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -4,7 +4,7 @@ */ #include "initialize_attitude.hpp" -#include +#include Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id) { diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 5766791ca..dfbcd52d7 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -4,7 +4,7 @@ */ #include "initialize_orbit.hpp" -#include +#include #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index 81d5bdbb9..d1834f177 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -5,7 +5,7 @@ #include "initialize_node.hpp" -#include +#include #include #include diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 6cf468cfe..384c69dc5 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -5,7 +5,7 @@ #include "initialize_temperature.hpp" -#include +#include #include #include diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 8a9a2278a..bfa18b7c6 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -5,7 +5,7 @@ #include "global_environment.hpp" -#include +#include #include "initialize_global_environment.hpp" #include "initialize_gnss_satellites.hpp" diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 6a0fc4621..4e8157a0e 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -4,7 +4,7 @@ */ #include "initialize_global_environment.hpp" -#include +#include #include #include diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index c223e6838..eb3b00bc0 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "initialize_gnss_satellites.hpp" -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index ca1283fd3..5aa0c5f92 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,7 +5,7 @@ #include "geomagnetic_field.hpp" -#include +#include #include #include diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 9cf037ec6..63d9110b6 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -5,7 +5,7 @@ #include "initialize_local_environment.hpp" -#include +#include #include diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index a5edb08fe..2cd5aa754 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,7 +4,7 @@ */ #include "local_environment.hpp" -#include +#include #include #include diff --git a/src/interface/LogOutput/InitLog.cpp b/src/interface/LogOutput/InitLog.cpp index 1ab6310ad..9f3713480 100644 --- a/src/interface/LogOutput/InitLog.cpp +++ b/src/interface/LogOutput/InitLog.cpp @@ -5,7 +5,7 @@ #include "InitLog.hpp" -#include +#include Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); diff --git a/src/interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp index 6546291fe..711c84555 100644 --- a/src/interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -5,7 +5,7 @@ #include "PowerPort.h" -#include +#include #include diff --git a/src/interface/InitInput/CMakeLists.txt b/src/interface/initialize/CMakeLists.txt similarity index 100% rename from src/interface/InitInput/CMakeLists.txt rename to src/interface/initialize/CMakeLists.txt diff --git a/src/interface/InitInput/IniAccess.cpp b/src/interface/initialize/IniAccess.cpp similarity index 100% rename from src/interface/InitInput/IniAccess.cpp rename to src/interface/initialize/IniAccess.cpp diff --git a/src/interface/InitInput/IniAccess.h b/src/interface/initialize/IniAccess.h similarity index 100% rename from src/interface/InitInput/IniAccess.h rename to src/interface/initialize/IniAccess.h diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index ab7515498..ad517010e 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -5,7 +5,7 @@ #include "simulation_case.hpp" -#include +#include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 07396c013..29898767e 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,7 +5,7 @@ #include "ground_station.hpp" -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 91d7b2350..c199dafcc 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -4,7 +4,7 @@ */ #include "sample_ground_station_components.hpp" -#include +#include SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 2f6f735cc..983dc61bf 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -5,7 +5,7 @@ #include "initialize_monte_carlo_simulation.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 2706ca33e..cd36a8ae9 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -5,7 +5,7 @@ #include "sample_components.hpp" -#include +#include #include "sample_port_configuration.hpp" diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 94e40793f..6018d73ec 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 5ba0252ea..78eab0211 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -5,7 +5,7 @@ #include "structure.hpp" -#include +#include #include From 8b79c1fbf6b0f40efd58eb4d39b55beca1545739 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 21:01:44 +0100 Subject: [PATCH 0254/1086] Rename IniAccess --- src/Component/AOCS/InitGnssReceiver.cpp | 2 +- src/Component/AOCS/InitGyro.cpp | 2 +- src/Component/AOCS/InitMagSensor.cpp | 2 +- src/Component/AOCS/InitMagTorquer.cpp | 2 +- src/Component/AOCS/InitRwModel.cpp | 2 +- src/Component/AOCS/InitStt.cpp | 2 +- src/Component/AOCS/InitSunSensor.cpp | 2 +- src/Component/Abstract/InitializeSensorBase_tfs.hpp | 2 +- src/Component/CommGS/AntennaRadiationPattern.cpp | 2 +- src/Component/CommGS/InitAntenna.cpp | 2 +- src/Component/CommGS/InitGsCalculator.cpp | 2 +- .../IdealComponents/InitializeForceGenerator.cpp | 2 +- .../IdealComponents/InitializeTorqueGenerator.cpp | 2 +- src/Component/Mission/Telescope/InitTelescope.cpp | 2 +- src/Component/Power/CsvScenarioInterface.cpp | 2 +- src/Component/Power/InitBat.cpp | 2 +- src/Component/Power/InitPcu_InitialStudy.cpp | 2 +- src/Component/Power/InitSap.cpp | 2 +- src/Component/Propulsion/InitSimpleThruster.cpp | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- src/dynamics/attitude/initialize_attitude.cpp | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/thermal/initialize_node.cpp | 2 +- src/dynamics/thermal/initialize_temperature.cpp | 2 +- src/environment/global/global_environment.cpp | 2 +- src/environment/global/initialize_global_environment.cpp | 2 +- src/environment/global/initialize_gnss_satellites.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/environment/local/initialize_local_environment.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/interface/LogOutput/InitLog.cpp | 2 +- src/interface/SpacecraftInOut/Ports/PowerPort.cpp | 2 +- src/interface/initialize/CMakeLists.txt | 2 +- .../{IniAccess.cpp => initialize_file_access.cpp} | 4 ++-- .../{IniAccess.h => initialize_file_access.hpp} | 9 +++++---- src/simulation/case/simulation_case.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- .../sample_ground_station_components.cpp | 2 +- .../initialize_monte_carlo_simulation.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- .../spacecraft/structure/initialize_structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.cpp | 2 +- 43 files changed, 48 insertions(+), 47 deletions(-) rename src/interface/initialize/{IniAccess.cpp => initialize_file_access.cpp} (98%) rename src/interface/initialize/{IniAccess.h => initialize_file_access.hpp} (95%) diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/Component/AOCS/InitGnssReceiver.cpp index c3244d09d..a115c9552 100644 --- a/src/Component/AOCS/InitGnssReceiver.cpp +++ b/src/Component/AOCS/InitGnssReceiver.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" typedef struct _gnssrecever_param { int prescaler; diff --git a/src/Component/AOCS/InitGyro.cpp b/src/Component/AOCS/InitGyro.cpp index 9c5da1158..9b6a295db 100644 --- a/src/Component/AOCS/InitGyro.cpp +++ b/src/Component/AOCS/InitGyro.cpp @@ -4,7 +4,7 @@ */ #include "InitGyro.hpp" -#include +#include #include "../Abstract/InitializeSensorBase.hpp" diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/Component/AOCS/InitMagSensor.cpp index 25c2c2df9..f419675ab 100644 --- a/src/Component/AOCS/InitMagSensor.cpp +++ b/src/Component/AOCS/InitMagSensor.cpp @@ -5,7 +5,7 @@ #include "InitMagSensor.hpp" #include "../Abstract/InitializeSensorBase.hpp" -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/Component/AOCS/InitMagTorquer.cpp index 96a41f775..621d68bf3 100644 --- a/src/Component/AOCS/InitMagTorquer.cpp +++ b/src/Component/AOCS/InitMagTorquer.cpp @@ -4,7 +4,7 @@ */ #include "InitMagTorquer.hpp" -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/Component/AOCS/InitRwModel.cpp index 094b5136d..6ffd72166 100644 --- a/src/Component/AOCS/InitRwModel.cpp +++ b/src/Component/AOCS/InitRwModel.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" // In order to share processing among initialization functions, variables should also be shared. These variables have internal linkages and cannot be // referenced from the outside. diff --git a/src/Component/AOCS/InitStt.cpp b/src/Component/AOCS/InitStt.cpp index 195e8daa1..9fad8fbd6 100644 --- a/src/Component/AOCS/InitStt.cpp +++ b/src/Component/AOCS/InitStt.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" using namespace std; diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/Component/AOCS/InitSunSensor.cpp index f4577c700..229deaa51 100644 --- a/src/Component/AOCS/InitSunSensor.cpp +++ b/src/Component/AOCS/InitSunSensor.cpp @@ -8,7 +8,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/Component/Abstract/InitializeSensorBase_tfs.hpp index a99b9864e..cb34e177d 100644 --- a/src/Component/Abstract/InitializeSensorBase_tfs.hpp +++ b/src/Component/Abstract/InitializeSensorBase_tfs.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, diff --git a/src/Component/CommGS/AntennaRadiationPattern.cpp b/src/Component/CommGS/AntennaRadiationPattern.cpp index f9957261b..63575eaa0 100644 --- a/src/Component/CommGS/AntennaRadiationPattern.cpp +++ b/src/Component/CommGS/AntennaRadiationPattern.cpp @@ -5,7 +5,7 @@ #include "AntennaRadiationPattern.hpp" -#include +#include #include #include diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/Component/CommGS/InitAntenna.cpp index 4180e8d2f..4aa45edab 100644 --- a/src/Component/CommGS/InitAntenna.cpp +++ b/src/Component/CommGS/InitAntenna.cpp @@ -10,7 +10,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" using libra::Vector; diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/Component/CommGS/InitGsCalculator.cpp index 65f952fc7..6e17e6ac8 100644 --- a/src/Component/CommGS/InitGsCalculator.cpp +++ b/src/Component/CommGS/InitGsCalculator.cpp @@ -8,7 +8,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" GScalculator InitGScalculator(const std::string fname) { IniAccess gs_conf(fname); diff --git a/src/Component/IdealComponents/InitializeForceGenerator.cpp b/src/Component/IdealComponents/InitializeForceGenerator.cpp index b776cecc1..4f55aecf2 100644 --- a/src/Component/IdealComponents/InitializeForceGenerator.cpp +++ b/src/Component/IdealComponents/InitializeForceGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeForceGenerator.hpp" -#include +#include ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp index b044d67d9..c5abfce47 100644 --- a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp +++ b/src/Component/IdealComponents/InitializeTorqueGenerator.cpp @@ -4,7 +4,7 @@ */ #include "InitializeTorqueGenerator.hpp" -#include +#include TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/Component/Mission/Telescope/InitTelescope.cpp index df5b7e6d1..8e76caec1 100644 --- a/src/Component/Mission/Telescope/InitTelescope.cpp +++ b/src/Component/Mission/Telescope/InitTelescope.cpp @@ -9,7 +9,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" using namespace std; diff --git a/src/Component/Power/CsvScenarioInterface.cpp b/src/Component/Power/CsvScenarioInterface.cpp index ba12ed4dc..bd4005202 100644 --- a/src/Component/Power/CsvScenarioInterface.cpp +++ b/src/Component/Power/CsvScenarioInterface.cpp @@ -5,7 +5,7 @@ #include "CsvScenarioInterface.h" -#include +#include bool CsvScenarioInterface::is_csv_senario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; diff --git a/src/Component/Power/InitBat.cpp b/src/Component/Power/InitBat.cpp index 61d727cb6..5863ea506 100644 --- a/src/Component/Power/InitBat.cpp +++ b/src/Component/Power/InitBat.cpp @@ -8,7 +8,7 @@ #include #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time) { IniAccess bat_conf(fname); diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/Component/Power/InitPcu_InitialStudy.cpp index a09f429de..6ad22ecb3 100644 --- a/src/Component/Power/InitPcu_InitialStudy.cpp +++ b/src/Component/Power/InitPcu_InitialStudy.cpp @@ -9,7 +9,7 @@ #include #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time) { diff --git a/src/Component/Power/InitSap.cpp b/src/Component/Power/InitSap.cpp index 435076a8f..ac83d340b 100644 --- a/src/Component/Power/InitSap.cpp +++ b/src/Component/Power/InitSap.cpp @@ -7,7 +7,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/Component/Propulsion/InitSimpleThruster.cpp index 759cdd0d3..b566c90c2 100644 --- a/src/Component/Propulsion/InitSimpleThruster.cpp +++ b/src/Component/Propulsion/InitSimpleThruster.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/IniAccess.h" +#include "interface/initialize/initialize_file_access.hpp" SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 4ae60a8fd..84412025f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -5,7 +5,7 @@ #include "disturbances.hpp" -#include +#include #include "air_drag.hpp" #include "geopotential.hpp" diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index a215a65ae..b658e98de 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -5,7 +5,7 @@ #include "initialize_disturbances.hpp" -#include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 616c2fb5d..75befde2f 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -4,7 +4,7 @@ */ #include "initialize_attitude.hpp" -#include +#include Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id) { diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index dfbcd52d7..86244a2e7 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -4,7 +4,7 @@ */ #include "initialize_orbit.hpp" -#include +#include #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index d1834f177..395a0e5b9 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -5,7 +5,7 @@ #include "initialize_node.hpp" -#include +#include #include #include diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 384c69dc5..6ec978304 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -5,7 +5,7 @@ #include "initialize_temperature.hpp" -#include +#include #include #include diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index bfa18b7c6..0e284c5f7 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -5,7 +5,7 @@ #include "global_environment.hpp" -#include +#include #include "initialize_global_environment.hpp" #include "initialize_gnss_satellites.hpp" diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 4e8157a0e..7d3b9fd9c 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -4,7 +4,7 @@ */ #include "initialize_global_environment.hpp" -#include +#include #include #include diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index eb3b00bc0..dbea9fd3c 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "initialize_gnss_satellites.hpp" -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 5aa0c5f92..8453a41c4 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,7 +5,7 @@ #include "geomagnetic_field.hpp" -#include +#include #include #include diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 63d9110b6..1d73ac665 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -5,7 +5,7 @@ #include "initialize_local_environment.hpp" -#include +#include #include diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 2cd5aa754..b69953c0d 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,7 +4,7 @@ */ #include "local_environment.hpp" -#include +#include #include #include diff --git a/src/interface/LogOutput/InitLog.cpp b/src/interface/LogOutput/InitLog.cpp index 9f3713480..4e450f779 100644 --- a/src/interface/LogOutput/InitLog.cpp +++ b/src/interface/LogOutput/InitLog.cpp @@ -5,7 +5,7 @@ #include "InitLog.hpp" -#include +#include Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); diff --git a/src/interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp index 711c84555..864d643db 100644 --- a/src/interface/SpacecraftInOut/Ports/PowerPort.cpp +++ b/src/interface/SpacecraftInOut/Ports/PowerPort.cpp @@ -5,7 +5,7 @@ #include "PowerPort.h" -#include +#include #include diff --git a/src/interface/initialize/CMakeLists.txt b/src/interface/initialize/CMakeLists.txt index ff0e73b1e..4299474c8 100644 --- a/src/interface/initialize/CMakeLists.txt +++ b/src/interface/initialize/CMakeLists.txt @@ -2,7 +2,7 @@ project(INI_ACC) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - IniAccess.cpp + initialize_file_access.cpp ) include(../../../common.cmake) diff --git a/src/interface/initialize/IniAccess.cpp b/src/interface/initialize/initialize_file_access.cpp similarity index 98% rename from src/interface/initialize/IniAccess.cpp rename to src/interface/initialize/initialize_file_access.cpp index e35b3cbe7..5624227e6 100644 --- a/src/interface/initialize/IniAccess.cpp +++ b/src/interface/initialize/initialize_file_access.cpp @@ -1,9 +1,9 @@ /** - * @file IniAccess.cpp + * @file initialize_file_access.cpp * @brief Class to read and get parameters for the `ini` format file */ -#include "IniAccess.h" +#include "initialize_file_access.hpp" #include diff --git a/src/interface/initialize/IniAccess.h b/src/interface/initialize/initialize_file_access.hpp similarity index 95% rename from src/interface/initialize/IniAccess.h rename to src/interface/initialize/initialize_file_access.hpp index d81590371..2e6860568 100644 --- a/src/interface/initialize/IniAccess.h +++ b/src/interface/initialize/initialize_file_access.hpp @@ -1,10 +1,11 @@ /** - * @file IniAccess.h + * @file initialize_file_access.hpp * @brief Class to read and get parameters for the `ini` format file */ -#ifndef __IniAccess_H__ -#define __IniAccess_H__ +#ifndef S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ +#define S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ + #define _CRT_SECURE_NO_WARNINGS #ifdef WIN32 @@ -168,4 +169,4 @@ void IniAccess::ReadVector(const char* section_name, const char* key_name, Vecto } } -#endif //__IniAccess_H__ +#endif // S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index ad517010e..1cc55c4b8 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -5,7 +5,7 @@ #include "simulation_case.hpp" -#include +#include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 29898767e..788a368c9 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,7 +5,7 @@ #include "ground_station.hpp" -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index c199dafcc..34c7a674c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -4,7 +4,7 @@ */ #include "sample_ground_station_components.hpp" -#include +#include SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 983dc61bf..c7dcb7ce5 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -5,7 +5,7 @@ #include "initialize_monte_carlo_simulation.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index cd36a8ae9..1c4b5bfd3 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -5,7 +5,7 @@ #include "sample_components.hpp" -#include +#include #include "sample_port_configuration.hpp" diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 6018d73ec..ffd481668 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 78eab0211..15beb5c57 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -5,7 +5,7 @@ #include "structure.hpp" -#include +#include #include From 74f9c5402580ef602528b2d979098cd6043d1785 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Feb 2023 21:39:15 +0100 Subject: [PATCH 0255/1086] Rename LogOutput --- CMakeLists.txt | 2 +- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Component/AOCS/Gyro.h | 2 +- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.cpp | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/RWModel.h | 4 ++-- src/Component/AOCS/STT.cpp | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/AOCS/SunSensor.cpp | 2 +- src/Component/AOCS/SunSensor.h | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/IdealComponents/ForceGenerator.hpp | 2 +- src/Component/IdealComponents/TorqueGenerator.hpp | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/Component/Power/BAT.h | 2 +- src/Component/Power/PCU.h | 2 +- src/Component/Power/PCU_InitialStudy.h | 2 +- src/Component/Power/SAP.h | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- src/Component/examples/example_change_structure.hpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/dynamics/thermal/node.hpp | 2 +- src/dynamics/thermal/temperature.hpp | 2 +- src/environment/global/celestial_information.cpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/global/simulation_time.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/interface/HilsInOut/HardwareMessage.h | 2 +- src/interface/{LogOutput => log_output}/CMakeLists.txt | 0 src/interface/{LogOutput => log_output}/ILoggable.h | 0 src/interface/{LogOutput => log_output}/InitLog.cpp | 0 src/interface/{LogOutput => log_output}/InitLog.hpp | 2 +- src/interface/{LogOutput => log_output}/LogUtility.h | 0 src/interface/{LogOutput => log_output}/Logger.cpp | 0 src/interface/{LogOutput => log_output}/Logger.h | 0 src/relative_information/relative_information.hpp | 4 ++-- src/s2e.cpp | 2 +- src/simulation/case/simulation_case.cpp | 2 +- src/simulation/case/simulation_case.hpp | 2 +- src/simulation/ground_station/ground_station.cpp | 4 ++-- src/simulation/simulation_configuration.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- 69 files changed, 67 insertions(+), 67 deletions(-) rename src/interface/{LogOutput => log_output}/CMakeLists.txt (100%) rename src/interface/{LogOutput => log_output}/ILoggable.h (100%) rename src/interface/{LogOutput => log_output}/InitLog.cpp (100%) rename src/interface/{LogOutput => log_output}/InitLog.hpp (92%) rename src/interface/{LogOutput => log_output}/LogUtility.h (100%) rename src/interface/{LogOutput => log_output}/Logger.cpp (100%) rename src/interface/{LogOutput => log_output}/Logger.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index fc9b5db04..994abfd14 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,7 +71,7 @@ add_subdirectory(src/disturbances) add_subdirectory(src/Component) add_subdirectory(src/relative_information) add_subdirectory(src/interface/initialize) -add_subdirectory(src/interface/LogOutput) +add_subdirectory(src/interface/log_output) add_subdirectory(src/interface/SpacecraftInOut) add_subdirectory(src/interface/HilsInOut) add_subdirectory(src/Library/igrf) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 8722ca7e6..6c3135ab4 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -5,7 +5,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/AOCS/Gyro.h b/src/Component/AOCS/Gyro.h index 5debea2ff..f166ab756 100644 --- a/src/Component/AOCS/Gyro.h +++ b/src/Component/AOCS/Gyro.h @@ -6,7 +6,7 @@ #ifndef Gyro_H_ #define Gyro_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index e564ec4b1..3c1b60e29 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,7 +6,7 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/Component/AOCS/MagTorquer.cpp index 10de9f6fa..a89e12e6d 100644 --- a/src/Component/AOCS/MagTorquer.cpp +++ b/src/Component/AOCS/MagTorquer.cpp @@ -5,7 +5,7 @@ #include "MagTorquer.h" -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index 5ec790cea..7a4a31c39 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,7 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index dc01736c2..332b5f4d2 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -5,8 +5,8 @@ #ifndef __RWModel_H__ #define __RWModel_H__ -#include -#include +#include +#include #include #include diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index 1d55a9899..b0524fdf3 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -5,7 +5,7 @@ #include "STT.h" -#include +#include #include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index ccc6785f1..f87908e2e 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -8,7 +8,7 @@ #ifndef __STT_H__ #define __STT_H__ -#include +#include #include #include diff --git a/src/Component/AOCS/SunSensor.cpp b/src/Component/AOCS/SunSensor.cpp index 9c6ab3590..79493cd54 100644 --- a/src/Component/AOCS/SunSensor.cpp +++ b/src/Component/AOCS/SunSensor.cpp @@ -8,7 +8,7 @@ #include #include using libra::NormalRand; -#include +#include #include using namespace std; diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index 5c5df07e8..a6f3421e8 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,7 +6,7 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include +#include #include #include diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 122a0e837..3160cc6d1 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,7 +6,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/Component/IdealComponents/ForceGenerator.hpp index 6b15a7556..817d831c5 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/Component/IdealComponents/ForceGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/Component/IdealComponents/TorqueGenerator.hpp index 2db0aea33..3545f6da7 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/Component/IdealComponents/TorqueGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index fcae00831..175e27310 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Power/BAT.h b/src/Component/Power/BAT.h index b5dda9648..7d9174c55 100644 --- a/src/Component/Power/BAT.h +++ b/src/Component/Power/BAT.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index c00e932ed..355bd3bd1 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Power/PCU_InitialStudy.h b/src/Component/Power/PCU_InitialStudy.h index cfc7b2483..06bd90df8 100644 --- a/src/Component/Power/PCU_InitialStudy.h +++ b/src/Component/Power/PCU_InitialStudy.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index 6fc673108..ebec5cbc1 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 2f3cd6425..37fc32b08 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index 70e82cdb7..e3c6e3ff7 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index ed9f3e3c9..d6b62aa00 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/LogOutput/LogUtility.h" +#include "../interface/log_output/LogUtility.h" using namespace std; using namespace libra; diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 310c420cb..8793bd6ea 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index c899fbf16..a70cf8d18 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -11,7 +11,7 @@ #include #include -#include "../interface/LogOutput/LogUtility.h" +#include "../interface/log_output/LogUtility.h" // #define DEBUG_GEOPOTENTIAL diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 147d578dc..0df875b6e 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index d18027667..cf76318d0 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/LogOutput/LogUtility.h" +#include "../interface/log_output/LogUtility.h" using namespace std; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 58a07d407..b62f19068 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 8b2e0c29c..7980accba 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,7 +9,7 @@ using libra::NormalRand; #include -#include "../interface/LogOutput/LogUtility.h" +#include "../interface/log_output/LogUtility.h" #include "../Library/math/GlobalRand.h" #include "../Library/math/RandomWalk.hpp" diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 391b39a68..c0a8ad612 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -11,7 +11,7 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 713075ef6..a0db6467f 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -7,7 +7,7 @@ #include -#include "../interface/LogOutput/LogUtility.h" +#include "../interface/log_output/LogUtility.h" SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b) : SurfaceForce(surfaces, cg_b) {} diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 6cce14c69..3a50ed108 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../Library/math/Vector.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index b2fb1b4cb..ed5168c19 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/LogOutput/ILoggable.h" +#include "../interface/log_output/ILoggable.h" #include "../Library/math/Vector.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index b985fea74..06d516b8f 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -4,7 +4,7 @@ */ #include "attitude.hpp" -#include +#include Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { omega_b_rad_s_ = libra::Vector<3>(0.0); diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 7ffded924..1a276a6af 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include +#include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index bbbc23eda..143e09e06 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index c66b76c35..9f87786d2 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,7 +4,7 @@ */ #include "controlled_attitude.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index d2153ea1c..9fd96a03e 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,7 +16,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index 71d8d8bcc..7a96a1aec 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_NODE_H_ #define S2E_DYNAMICS_THERMAL_NODE_H_ -#include +#include #include #include diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index c2437b77c..426e81297 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ #define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ -#include +#include #include #include diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index de3733d8e..2dcb0e75b 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -6,7 +6,7 @@ #include "celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index eb2bd2a80..034bceb7d 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,7 +10,7 @@ #include #include -#include "interface/LogOutput/ILoggable.h" +#include "interface/log_output/ILoggable.h" #include "Library/math/MatVec.hpp" #include "Library/math/Matrix.hpp" #include "Library/math/Quaternion.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index ad0356572..be1e9f6dc 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,7 +10,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include +#include #include #include diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 67e55673b..d53393ed9 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ -#include +#include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 9492f5428..e51698b0a 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "gnss_satellites.hpp" -#include +#include #include //for jday() #include //for gstime() diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 8930b0a0a..e207070a4 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include +#include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 2349b19af..00d749fe4 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include +#include #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 5d9dfb151..74139c29b 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,7 +12,7 @@ #include // #include -#include +#include #include #include #include diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 07b6a908d..aee654506 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,7 +5,7 @@ #include "atmosphere.hpp" -#include +#include #include #include diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 8feb4112a..04284ddf2 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,7 +7,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 7883298fe..4b111136a 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -11,7 +11,7 @@ using libra::Vector; #include using libra::Quaternion; -#include +#include /** * @class MagEnvironment diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 18f0b6180..3c0cfed5c 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -5,7 +5,7 @@ #include "local_celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index ccf26e439..d68503267 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,7 +4,7 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 543177846..960d6e57e 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/interface/HilsInOut/HardwareMessage.h b/src/interface/HilsInOut/HardwareMessage.h index d8484d3c5..4721202e5 100644 --- a/src/interface/HilsInOut/HardwareMessage.h +++ b/src/interface/HilsInOut/HardwareMessage.h @@ -9,7 +9,7 @@ #include -#include "../LogOutput/ILoggable.h" +#include "../log_output/ILoggable.h" #include "ComPortInterface.h" typedef unsigned short int crc_t; diff --git a/src/interface/LogOutput/CMakeLists.txt b/src/interface/log_output/CMakeLists.txt similarity index 100% rename from src/interface/LogOutput/CMakeLists.txt rename to src/interface/log_output/CMakeLists.txt diff --git a/src/interface/LogOutput/ILoggable.h b/src/interface/log_output/ILoggable.h similarity index 100% rename from src/interface/LogOutput/ILoggable.h rename to src/interface/log_output/ILoggable.h diff --git a/src/interface/LogOutput/InitLog.cpp b/src/interface/log_output/InitLog.cpp similarity index 100% rename from src/interface/LogOutput/InitLog.cpp rename to src/interface/log_output/InitLog.cpp diff --git a/src/interface/LogOutput/InitLog.hpp b/src/interface/log_output/InitLog.hpp similarity index 92% rename from src/interface/LogOutput/InitLog.hpp rename to src/interface/log_output/InitLog.hpp index a1dadfab0..57bb2b029 100644 --- a/src/interface/LogOutput/InitLog.hpp +++ b/src/interface/log_output/InitLog.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitLog diff --git a/src/interface/LogOutput/LogUtility.h b/src/interface/log_output/LogUtility.h similarity index 100% rename from src/interface/LogOutput/LogUtility.h rename to src/interface/log_output/LogUtility.h diff --git a/src/interface/LogOutput/Logger.cpp b/src/interface/log_output/Logger.cpp similarity index 100% rename from src/interface/LogOutput/Logger.cpp rename to src/interface/log_output/Logger.cpp diff --git a/src/interface/LogOutput/Logger.h b/src/interface/log_output/Logger.h similarity index 100% rename from src/interface/LogOutput/Logger.h rename to src/interface/log_output/Logger.h diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 890219979..945b543f7 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -9,8 +9,8 @@ #include #include "../dynamics/dynamics.hpp" -#include "../interface/LogOutput/ILoggable.h" -#include "../interface/LogOutput/Logger.h" +#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/Logger.h" /** * @class RelativeInformation diff --git a/src/s2e.cpp b/src/s2e.cpp index f40432400..836eed9ee 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -15,7 +15,7 @@ #include // Simulator includes -#include "interface/LogOutput/Logger.h" +#include "interface/log_output/Logger.h" // Add custom include files #include "simulation/case/sample_case.hpp" diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 1cc55c4b8..79ca7a6cf 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include SimulationCase::SimulationCase(std::string ini_base) { diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 45b294aaa..e9dc335cf 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include +#include #include #include diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 788a368c9..45e54a2a6 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,8 +6,8 @@ #include "ground_station.hpp" #include -#include -#include +#include +#include #include #include diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index 09d1a6272..8c7cf5083 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/LogOutput/Logger.h" +#include "../interface/log_output/Logger.h" /** * @struct SimulationConfig diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index 284aa46b0..e80eff174 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include +#include #include diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index d33a15e89..9c3ecd918 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -5,8 +5,8 @@ #include "spacecraft.hpp" -#include -#include +#include +#include Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { Initialize(sim_config, glo_env, sat_id); From 2df92c4b8583696f279dc525e77d64ecc8d01065 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 08:37:57 +0100 Subject: [PATCH 0256/1086] Rename InitLog --- src/interface/log_output/CMakeLists.txt | 2 +- .../log_output/{InitLog.cpp => initialize_log.cpp} | 4 ++-- .../log_output/{InitLog.hpp => initialize_log.hpp} | 7 +++++-- src/simulation/case/simulation_case.cpp | 3 +-- 4 files changed, 9 insertions(+), 7 deletions(-) rename src/interface/log_output/{InitLog.cpp => initialize_log.cpp} (93%) rename src/interface/log_output/{InitLog.hpp => initialize_log.hpp} (73%) diff --git a/src/interface/log_output/CMakeLists.txt b/src/interface/log_output/CMakeLists.txt index 5f5af7c20..31e073dd4 100644 --- a/src/interface/log_output/CMakeLists.txt +++ b/src/interface/log_output/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC Logger.cpp - InitLog.cpp + initialize_log.cpp ) include(../../../common.cmake) diff --git a/src/interface/log_output/InitLog.cpp b/src/interface/log_output/initialize_log.cpp similarity index 93% rename from src/interface/log_output/InitLog.cpp rename to src/interface/log_output/initialize_log.cpp index 4e450f779..fdab0cd32 100644 --- a/src/interface/log_output/InitLog.cpp +++ b/src/interface/log_output/initialize_log.cpp @@ -1,9 +1,9 @@ /** - * @file InitLog.cpp + * @file initialize_log.cpp * @brief Initialize function for Log output */ -#include "InitLog.hpp" +#include "initialize_log.hpp" #include diff --git a/src/interface/log_output/InitLog.hpp b/src/interface/log_output/initialize_log.hpp similarity index 73% rename from src/interface/log_output/InitLog.hpp rename to src/interface/log_output/initialize_log.hpp index 57bb2b029..34f15a27c 100644 --- a/src/interface/log_output/InitLog.hpp +++ b/src/interface/log_output/initialize_log.hpp @@ -1,9 +1,10 @@ /** - * @file InitLog.hpp + * @file initialize_log.hpp * @brief Initialize function for Log output */ -#pragma once +#ifndef S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ +#define S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ #include @@ -21,3 +22,5 @@ Logger* InitLog(std::string file_name); * @param [in] enable: Enable flag for logging */ Logger* InitLogMC(std::string file_name, bool enable); + +#endif // S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 79ca7a6cf..1c55ad864 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -6,8 +6,7 @@ #include "simulation_case.hpp" #include - -#include +#include #include SimulationCase::SimulationCase(std::string ini_base) { From 27f9633dcdb212a1e3073231edd76985c95b6830 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 08:40:02 +0100 Subject: [PATCH 0257/1086] Rename Logger --- src/Component/AOCS/MagTorquer.cpp | 2 +- src/Component/AOCS/RWModel.h | 2 +- src/Component/IdealComponents/ForceGenerator.hpp | 2 +- src/Component/IdealComponents/TorqueGenerator.hpp | 2 +- src/Component/Propulsion/SimpleThruster.h | 2 +- src/dynamics/thermal/node.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/interface/log_output/CMakeLists.txt | 2 +- src/interface/log_output/initialize_log.hpp | 2 +- src/interface/log_output/{Logger.cpp => logger.cpp} | 4 ++-- src/interface/log_output/{Logger.h => logger.hpp} | 9 +++++---- src/relative_information/relative_information.hpp | 2 +- src/s2e.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- src/simulation/simulation_configuration.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 2 +- 17 files changed, 22 insertions(+), 21 deletions(-) rename src/interface/log_output/{Logger.cpp => logger.cpp} (98%) rename src/interface/log_output/{Logger.h => logger.hpp} (95%) diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/Component/AOCS/MagTorquer.cpp index a89e12e6d..65e9bb015 100644 --- a/src/Component/AOCS/MagTorquer.cpp +++ b/src/Component/AOCS/MagTorquer.cpp @@ -5,7 +5,7 @@ #include "MagTorquer.h" -#include +#include #include #include diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index 332b5f4d2..0cd9d431c 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -6,7 +6,7 @@ #ifndef __RWModel_H__ #define __RWModel_H__ #include -#include +#include #include #include diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/Component/IdealComponents/ForceGenerator.hpp index 817d831c5..6728ff788 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/Component/IdealComponents/ForceGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/Component/IdealComponents/TorqueGenerator.hpp index 3545f6da7..1c600b0a2 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/Component/IdealComponents/TorqueGenerator.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/Component/Propulsion/SimpleThruster.h index 37fc32b08..f88d75e4a 100644 --- a/src/Component/Propulsion/SimpleThruster.h +++ b/src/Component/Propulsion/SimpleThruster.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index 7a96a1aec..70105b56a 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_NODE_H_ #define S2E_DYNAMICS_THERMAL_NODE_H_ -#include +#include #include #include diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index d53393ed9..1ca3d2098 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ -#include +#include #include diff --git a/src/interface/log_output/CMakeLists.txt b/src/interface/log_output/CMakeLists.txt index 31e073dd4..eb2f6d9f5 100644 --- a/src/interface/log_output/CMakeLists.txt +++ b/src/interface/log_output/CMakeLists.txt @@ -2,7 +2,7 @@ project(LOG_OUT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Logger.cpp + logger.cpp initialize_log.cpp ) diff --git a/src/interface/log_output/initialize_log.hpp b/src/interface/log_output/initialize_log.hpp index 34f15a27c..a80072e4e 100644 --- a/src/interface/log_output/initialize_log.hpp +++ b/src/interface/log_output/initialize_log.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ #define S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ -#include +#include /** * @fn InitLog diff --git a/src/interface/log_output/Logger.cpp b/src/interface/log_output/logger.cpp similarity index 98% rename from src/interface/log_output/Logger.cpp rename to src/interface/log_output/logger.cpp index 4d2ac9e72..79f8424e5 100644 --- a/src/interface/log_output/Logger.cpp +++ b/src/interface/log_output/logger.cpp @@ -1,9 +1,9 @@ /** - * @file Logger.cpp + * @file logger.cpp * @brief Class to manage log output file */ -#include "Logger.h" +#include "logger.hpp" #include #include diff --git a/src/interface/log_output/Logger.h b/src/interface/log_output/logger.hpp similarity index 95% rename from src/interface/log_output/Logger.h rename to src/interface/log_output/logger.hpp index 204736b82..869bbd60c 100644 --- a/src/interface/log_output/Logger.h +++ b/src/interface/log_output/logger.hpp @@ -1,10 +1,11 @@ /** - * @file Logger.h + * @file logger.hpp * @brief Class to manage log output file */ -#ifndef __LOGGER_H__ -#define __LOGGER_H__ +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ +#define S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ + #define _CRT_SECURE_NO_WARNINGS #include @@ -129,4 +130,4 @@ void Logger::Enable(bool enable) { is_enabled_ = enable; } std::string Logger::GetLogPath() const { return directory_path_; } -#endif //__Logger_H__ +#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 945b543f7..b105af26a 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -10,7 +10,7 @@ #include "../dynamics/dynamics.hpp" #include "../interface/log_output/ILoggable.h" -#include "../interface/log_output/Logger.h" +#include "../interface/log_output/logger.hpp" /** * @class RelativeInformation diff --git a/src/s2e.cpp b/src/s2e.cpp index 836eed9ee..93048aa20 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -15,7 +15,7 @@ #include // Simulator includes -#include "interface/log_output/Logger.h" +#include "interface/log_output/logger.hpp" // Add custom include files #include "simulation/case/sample_case.hpp" diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 45e54a2a6..295d3bc30 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index 8c7cf5083..f68187503 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/log_output/Logger.h" +#include "../interface/log_output/logger.hpp" /** * @struct SimulationConfig diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index e80eff174..e6b88294c 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include +#include #include diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 9c3ecd918..097d7a464 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -6,7 +6,7 @@ #include "spacecraft.hpp" #include -#include +#include Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { Initialize(sim_config, glo_env, sat_id); From a7307f297e7237f8740c9321e599544c040067f0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 08:42:58 +0100 Subject: [PATCH 0258/1086] Rename LogUtility --- src/Component/AOCS/STT.cpp | 2 +- src/Component/AOCS/SunSensor.cpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/environment/global/celestial_information.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- src/interface/log_output/ILoggable.h | 2 +- src/interface/log_output/{LogUtility.h => log_utility.hpp} | 7 +++++-- src/simulation/ground_station/ground_station.cpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 2 +- 19 files changed, 23 insertions(+), 20 deletions(-) rename src/interface/log_output/{LogUtility.h => log_utility.hpp} (96%) diff --git a/src/Component/AOCS/STT.cpp b/src/Component/AOCS/STT.cpp index b0524fdf3..d00ea3cec 100644 --- a/src/Component/AOCS/STT.cpp +++ b/src/Component/AOCS/STT.cpp @@ -5,7 +5,7 @@ #include "STT.h" -#include +#include #include #include diff --git a/src/Component/AOCS/SunSensor.cpp b/src/Component/AOCS/SunSensor.cpp index 79493cd54..239a31318 100644 --- a/src/Component/AOCS/SunSensor.cpp +++ b/src/Component/AOCS/SunSensor.cpp @@ -8,7 +8,7 @@ #include #include using libra::NormalRand; -#include +#include #include using namespace std; diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index d6b62aa00..a90a45a61 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/LogUtility.h" +#include "../interface/log_output/log_utility.hpp" using namespace std; using namespace libra; diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index a70cf8d18..6e904a45a 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -11,7 +11,7 @@ #include #include -#include "../interface/log_output/LogUtility.h" +#include "../interface/log_output/log_utility.hpp" // #define DEBUG_GEOPOTENTIAL diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index cf76318d0..23668b736 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/LogUtility.h" +#include "../interface/log_output/log_utility.hpp" using namespace std; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 7980accba..e162c2ec8 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,7 +9,7 @@ using libra::NormalRand; #include -#include "../interface/log_output/LogUtility.h" +#include "../interface/log_output/log_utility.hpp" #include "../Library/math/GlobalRand.h" #include "../Library/math/RandomWalk.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index a0db6467f..fd3fb08bd 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -7,7 +7,7 @@ #include -#include "../interface/log_output/LogUtility.h" +#include "../interface/log_output/log_utility.hpp" SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b) : SurfaceForce(surfaces, cg_b) {} diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 06d516b8f..78cdbb38c 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -4,7 +4,7 @@ */ #include "attitude.hpp" -#include +#include Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { omega_b_rad_s_ = libra::Vector<3>(0.0); diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 143e09e06..cebc69da2 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 9f87786d2..796074fc3 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,7 +4,7 @@ */ #include "controlled_attitude.hpp" -#include +#include #include #include diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 2dcb0e75b..0f96e05a0 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -6,7 +6,7 @@ #include "celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index e51698b0a..cc3959849 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,7 +5,7 @@ #include "gnss_satellites.hpp" -#include +#include #include //for jday() #include //for gstime() diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index aee654506..866243f18 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,7 +5,7 @@ #include "atmosphere.hpp" -#include +#include #include #include diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 3c0cfed5c..f9d0e90c7 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -5,7 +5,7 @@ #include "local_celestial_information.hpp" -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index d68503267..18d2cc398 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,7 +4,7 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include +#include #include #include diff --git a/src/interface/log_output/ILoggable.h b/src/interface/log_output/ILoggable.h index 2ce72e723..1bf332304 100644 --- a/src/interface/log_output/ILoggable.h +++ b/src/interface/log_output/ILoggable.h @@ -6,7 +6,7 @@ #pragma once #include -#include "LogUtility.h" // This is not necessary but include here for convenience +#include "log_utility.hpp" // This is not necessary but include here for convenience /** * @class ILoggable diff --git a/src/interface/log_output/LogUtility.h b/src/interface/log_output/log_utility.hpp similarity index 96% rename from src/interface/log_output/LogUtility.h rename to src/interface/log_output/log_utility.hpp index 904437bd2..e83fb9dca 100644 --- a/src/interface/log_output/LogUtility.h +++ b/src/interface/log_output/log_utility.hpp @@ -1,9 +1,10 @@ /** - * @file LogUtility.h + * @file log_utility.hpp * @brief Utility functions to support logging for users */ -#pragma once +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ +#define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ #include #include @@ -157,3 +158,5 @@ std::string WriteQuaternion(std::string name, std::string frame) { } return str_tmp.str(); } + +#endif // S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 295d3bc30..ed04de391 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,7 +6,7 @@ #include "ground_station.hpp" #include -#include +#include #include #include diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 097d7a464..35837bf0f 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -5,7 +5,7 @@ #include "spacecraft.hpp" -#include +#include #include Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { From 7ce2cab589b4735292b86875c6e404c4f3e6a106 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 09:47:59 +0100 Subject: [PATCH 0259/1086] Rename ILoggable --- src/Component/AOCS/GNSSReceiver.h | 2 +- src/Component/AOCS/Gyro.h | 2 +- src/Component/AOCS/MagSensor.h | 2 +- src/Component/AOCS/MagTorquer.h | 2 +- src/Component/AOCS/RWModel.h | 2 +- src/Component/AOCS/STT.h | 2 +- src/Component/AOCS/SunSensor.h | 2 +- src/Component/CommGS/GScalculator.h | 2 +- src/Component/Mission/Telescope/Telescope.h | 2 +- src/Component/Power/BAT.h | 2 +- src/Component/Power/PCU.h | 2 +- src/Component/Power/PCU_InitialStudy.h | 2 +- src/Component/Power/SAP.h | 2 +- src/Component/examples/example_change_structure.hpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/dynamics/thermal/temperature.hpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/global/simulation_time.hpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/interface/HilsInOut/HardwareMessage.h | 2 +- src/interface/log_output/{ILoggable.h => loggable.hpp} | 8 ++++++-- src/interface/log_output/logger.hpp | 2 +- src/relative_information/relative_information.hpp | 2 +- src/simulation/case/simulation_case.hpp | 2 +- 36 files changed, 41 insertions(+), 37 deletions(-) rename src/interface/log_output/{ILoggable.h => loggable.hpp} (82%) diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/Component/AOCS/GNSSReceiver.h index 6c3135ab4..0d28c1641 100644 --- a/src/Component/AOCS/GNSSReceiver.h +++ b/src/Component/AOCS/GNSSReceiver.h @@ -5,7 +5,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/AOCS/Gyro.h b/src/Component/AOCS/Gyro.h index f166ab756..245d6a434 100644 --- a/src/Component/AOCS/Gyro.h +++ b/src/Component/AOCS/Gyro.h @@ -6,7 +6,7 @@ #ifndef Gyro_H_ #define Gyro_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagSensor.h b/src/Component/AOCS/MagSensor.h index 3c1b60e29..ac0d0443a 100644 --- a/src/Component/AOCS/MagSensor.h +++ b/src/Component/AOCS/MagSensor.h @@ -6,7 +6,7 @@ #ifndef MagSensor_H_ #define MagSensor_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/MagTorquer.h b/src/Component/AOCS/MagTorquer.h index 7a4a31c39..42b4ebfcb 100644 --- a/src/Component/AOCS/MagTorquer.h +++ b/src/Component/AOCS/MagTorquer.h @@ -6,7 +6,7 @@ #ifndef MTQ_H_ #define MTQ_H_ -#include +#include #include #include diff --git a/src/Component/AOCS/RWModel.h b/src/Component/AOCS/RWModel.h index 0cd9d431c..7a01033ae 100644 --- a/src/Component/AOCS/RWModel.h +++ b/src/Component/AOCS/RWModel.h @@ -5,7 +5,7 @@ #ifndef __RWModel_H__ #define __RWModel_H__ -#include +#include #include #include diff --git a/src/Component/AOCS/STT.h b/src/Component/AOCS/STT.h index f87908e2e..d2fae33ed 100644 --- a/src/Component/AOCS/STT.h +++ b/src/Component/AOCS/STT.h @@ -8,7 +8,7 @@ #ifndef __STT_H__ #define __STT_H__ -#include +#include #include #include diff --git a/src/Component/AOCS/SunSensor.h b/src/Component/AOCS/SunSensor.h index a6f3421e8..7a1125498 100644 --- a/src/Component/AOCS/SunSensor.h +++ b/src/Component/AOCS/SunSensor.h @@ -6,7 +6,7 @@ #ifndef __SunSensor_H__ #define __SunSensor_H__ -#include +#include #include #include diff --git a/src/Component/CommGS/GScalculator.h b/src/Component/CommGS/GScalculator.h index 3160cc6d1..12725a6df 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/Component/CommGS/GScalculator.h @@ -6,7 +6,7 @@ #pragma once -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/Component/Mission/Telescope/Telescope.h index 175e27310..6f9892ef9 100644 --- a/src/Component/Mission/Telescope/Telescope.h +++ b/src/Component/Mission/Telescope/Telescope.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include #include diff --git a/src/Component/Power/BAT.h b/src/Component/Power/BAT.h index 7d9174c55..7ba8fa777 100644 --- a/src/Component/Power/BAT.h +++ b/src/Component/Power/BAT.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index 355bd3bd1..fdea4baf7 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Power/PCU_InitialStudy.h b/src/Component/Power/PCU_InitialStudy.h index 06bd90df8..0c6899abb 100644 --- a/src/Component/Power/PCU_InitialStudy.h +++ b/src/Component/Power/PCU_InitialStudy.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include diff --git a/src/Component/Power/SAP.h b/src/Component/Power/SAP.h index ebec5cbc1..da456799e 100644 --- a/src/Component/Power/SAP.h +++ b/src/Component/Power/SAP.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/examples/example_change_structure.hpp b/src/Component/examples/example_change_structure.hpp index e3c6e3ff7..e7dcafb88 100644 --- a/src/Component/examples/example_change_structure.hpp +++ b/src/Component/examples/example_change_structure.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 8793bd6ea..36d27e2f2 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 0df875b6e..9f38386df 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index b62f19068..236906996 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index c0a8ad612..ed9a093a6 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -11,7 +11,7 @@ #include "../Library/math/Vector.hpp" using libra::Vector; -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 3a50ed108..c4acdd156 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../Library/math/Vector.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index ed5168c19..8d9fe2763 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../Library/math/Vector.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 1a276a6af..e08710dd5 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include +#include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 9fd96a03e..edf94a3a5 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,7 +16,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 426e81297..2d9b10e32 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ #define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ -#include +#include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 034bceb7d..1553f3b72 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,7 +10,7 @@ #include #include -#include "interface/log_output/ILoggable.h" +#include "interface/log_output/loggable.hpp" #include "Library/math/MatVec.hpp" #include "Library/math/Matrix.hpp" #include "Library/math/Quaternion.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index be1e9f6dc..95c3518bd 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,7 +10,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include +#include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index e207070a4..4ebfed84a 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include +#include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 00d749fe4..5db97e510 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include +#include #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 74139c29b..df099a6aa 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,7 +12,7 @@ #include // #include -#include +#include #include #include #include diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 04284ddf2..a8a4e5465 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,7 +7,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 4b111136a..3c7bbb96c 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -11,7 +11,7 @@ using libra::Vector; #include using libra::Quaternion; -#include +#include /** * @class MagEnvironment diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 960d6e57e..13cd47d2d 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/interface/HilsInOut/HardwareMessage.h b/src/interface/HilsInOut/HardwareMessage.h index 4721202e5..5cde7e360 100644 --- a/src/interface/HilsInOut/HardwareMessage.h +++ b/src/interface/HilsInOut/HardwareMessage.h @@ -9,7 +9,7 @@ #include -#include "../log_output/ILoggable.h" +#include "../log_output/loggable.hpp" #include "ComPortInterface.h" typedef unsigned short int crc_t; diff --git a/src/interface/log_output/ILoggable.h b/src/interface/log_output/loggable.hpp similarity index 82% rename from src/interface/log_output/ILoggable.h rename to src/interface/log_output/loggable.hpp index 1bf332304..b56cbdf27 100644 --- a/src/interface/log_output/ILoggable.h +++ b/src/interface/log_output/loggable.hpp @@ -1,9 +1,11 @@ /** - * @file ILoggable.h + * @file loggable.hpp * @brief Abstract class to manage logging */ -#pragma once +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ +#define S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ + #include #include "log_utility.hpp" // This is not necessary but include here for convenience @@ -31,3 +33,5 @@ class ILoggable { bool IsLogEnabled = true; //!< Log enable flag }; + +#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ diff --git a/src/interface/log_output/logger.hpp b/src/interface/log_output/logger.hpp index 869bbd60c..cdc5f09a0 100644 --- a/src/interface/log_output/logger.hpp +++ b/src/interface/log_output/logger.hpp @@ -12,7 +12,7 @@ #include #include -#include "ILoggable.h" +#include "loggable.hpp" /** * @class Logger diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index b105af26a..fec371cce 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -9,7 +9,7 @@ #include #include "../dynamics/dynamics.hpp" -#include "../interface/log_output/ILoggable.h" +#include "../interface/log_output/loggable.hpp" #include "../interface/log_output/logger.hpp" /** diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index e9dc335cf..c55888f03 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include +#include #include #include From 31000161901cc7485de13f08dd5225d6548f2cff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 09:53:46 +0100 Subject: [PATCH 0260/1086] Rename HilsInOut directory --- CMakeLists.txt | 2 +- src/Component/Abstract/I2cControllerCommunicationBase.h | 2 +- src/Component/Abstract/ObcCommunicationBase.h | 2 +- src/Component/Abstract/ObcI2cTargetCommunicationBase.h | 2 +- src/interface/{HilsInOut => hils}/CMakeLists.txt | 0 src/interface/{HilsInOut => hils}/ComPortInterface.cpp | 0 src/interface/{HilsInOut => hils}/ComPortInterface.h | 0 src/interface/{HilsInOut => hils}/HardwareMessage.cpp | 0 src/interface/{HilsInOut => hils}/HardwareMessage.h | 0 src/interface/{HilsInOut => hils}/HilsPortManager.cpp | 0 src/interface/{HilsInOut => hils}/HilsPortManager.h | 0 src/interface/{HilsInOut => hils}/InitCosmosWrapper.cpp | 2 +- src/interface/{HilsInOut => hils}/InitHardwareMessage.cpp | 2 +- src/interface/{HilsInOut => hils}/Ports/HilsI2cTargetPort.cpp | 0 src/interface/{HilsInOut => hils}/Ports/HilsI2cTargetPort.h | 0 src/interface/{HilsInOut => hils}/Ports/HilsUartPort.cpp | 0 src/interface/{HilsInOut => hils}/Ports/HilsUartPort.h | 0 src/s2e.cpp | 4 ++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 19 files changed, 9 insertions(+), 9 deletions(-) rename src/interface/{HilsInOut => hils}/CMakeLists.txt (100%) rename src/interface/{HilsInOut => hils}/ComPortInterface.cpp (100%) rename src/interface/{HilsInOut => hils}/ComPortInterface.h (100%) rename src/interface/{HilsInOut => hils}/HardwareMessage.cpp (100%) rename src/interface/{HilsInOut => hils}/HardwareMessage.h (100%) rename src/interface/{HilsInOut => hils}/HilsPortManager.cpp (100%) rename src/interface/{HilsInOut => hils}/HilsPortManager.h (100%) rename src/interface/{HilsInOut => hils}/InitCosmosWrapper.cpp (95%) rename src/interface/{HilsInOut => hils}/InitHardwareMessage.cpp (95%) rename src/interface/{HilsInOut => hils}/Ports/HilsI2cTargetPort.cpp (100%) rename src/interface/{HilsInOut => hils}/Ports/HilsI2cTargetPort.h (100%) rename src/interface/{HilsInOut => hils}/Ports/HilsUartPort.cpp (100%) rename src/interface/{HilsInOut => hils}/Ports/HilsUartPort.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 994abfd14..043ffeb78 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,7 +73,7 @@ add_subdirectory(src/relative_information) add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/log_output) add_subdirectory(src/interface/SpacecraftInOut) -add_subdirectory(src/interface/HilsInOut) +add_subdirectory(src/interface/hils) add_subdirectory(src/Library/igrf) add_subdirectory(src/Library/inih) add_subdirectory(src/Library/math) diff --git a/src/Component/Abstract/I2cControllerCommunicationBase.h b/src/Component/Abstract/I2cControllerCommunicationBase.h index e9671f0c7..e687f1fa9 100644 --- a/src/Component/Abstract/I2cControllerCommunicationBase.h +++ b/src/Component/Abstract/I2cControllerCommunicationBase.h @@ -3,7 +3,7 @@ * @brief This class simulates the I2C Controller communication with the I2C Target. */ #pragma once -#include "../../interface/HilsInOut/HilsPortManager.h" +#include "../../interface/hils/HilsPortManager.h" #include "ObcCommunicationBase.h" /** diff --git a/src/Component/Abstract/ObcCommunicationBase.h b/src/Component/Abstract/ObcCommunicationBase.h index d0a23045a..ee8466583 100644 --- a/src/Component/Abstract/ObcCommunicationBase.h +++ b/src/Component/Abstract/ObcCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for serial communication (e.g., UART) with OBC flight software */ #pragma once -#include +#include #include "../CDH/OBC.h" diff --git a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h index 36133579a..d8df6ab66 100644 --- a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h +++ b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for I2C communication as target side with OBC flight software */ #pragma once -#include "../../interface/HilsInOut/HilsPortManager.h" +#include "../../interface/hils/HilsPortManager.h" #include "../CDH/OBC.h" #include "ObcCommunicationBase.h" diff --git a/src/interface/HilsInOut/CMakeLists.txt b/src/interface/hils/CMakeLists.txt similarity index 100% rename from src/interface/HilsInOut/CMakeLists.txt rename to src/interface/hils/CMakeLists.txt diff --git a/src/interface/HilsInOut/ComPortInterface.cpp b/src/interface/hils/ComPortInterface.cpp similarity index 100% rename from src/interface/HilsInOut/ComPortInterface.cpp rename to src/interface/hils/ComPortInterface.cpp diff --git a/src/interface/HilsInOut/ComPortInterface.h b/src/interface/hils/ComPortInterface.h similarity index 100% rename from src/interface/HilsInOut/ComPortInterface.h rename to src/interface/hils/ComPortInterface.h diff --git a/src/interface/HilsInOut/HardwareMessage.cpp b/src/interface/hils/HardwareMessage.cpp similarity index 100% rename from src/interface/HilsInOut/HardwareMessage.cpp rename to src/interface/hils/HardwareMessage.cpp diff --git a/src/interface/HilsInOut/HardwareMessage.h b/src/interface/hils/HardwareMessage.h similarity index 100% rename from src/interface/HilsInOut/HardwareMessage.h rename to src/interface/hils/HardwareMessage.h diff --git a/src/interface/HilsInOut/HilsPortManager.cpp b/src/interface/hils/HilsPortManager.cpp similarity index 100% rename from src/interface/HilsInOut/HilsPortManager.cpp rename to src/interface/hils/HilsPortManager.cpp diff --git a/src/interface/HilsInOut/HilsPortManager.h b/src/interface/hils/HilsPortManager.h similarity index 100% rename from src/interface/HilsInOut/HilsPortManager.h rename to src/interface/hils/HilsPortManager.h diff --git a/src/interface/HilsInOut/InitCosmosWrapper.cpp b/src/interface/hils/InitCosmosWrapper.cpp similarity index 95% rename from src/interface/HilsInOut/InitCosmosWrapper.cpp rename to src/interface/hils/InitCosmosWrapper.cpp index 30540e7ff..5ca2e451d 100644 --- a/src/interface/HilsInOut/InitCosmosWrapper.cpp +++ b/src/interface/hils/InitCosmosWrapper.cpp @@ -3,7 +3,7 @@ * @brief Initialize function for COSMOSWrapper */ -#include "../HilsInOut/COSMOSWrapper.h" +#include "../hils/COSMOSWrapper.h" #include "Initialize.h" /** diff --git a/src/interface/HilsInOut/InitHardwareMessage.cpp b/src/interface/hils/InitHardwareMessage.cpp similarity index 95% rename from src/interface/HilsInOut/InitHardwareMessage.cpp rename to src/interface/hils/InitHardwareMessage.cpp index 2e05c6220..578d2cf6c 100644 --- a/src/interface/HilsInOut/InitHardwareMessage.cpp +++ b/src/interface/hils/InitHardwareMessage.cpp @@ -3,7 +3,7 @@ * @brief Initialize function for HardwareMessage */ -#include "../HilsInOut/HardwareMessage.h" +#include "../hils/HardwareMessage.h" #include "Initialize.h" /** diff --git a/src/interface/HilsInOut/Ports/HilsI2cTargetPort.cpp b/src/interface/hils/Ports/HilsI2cTargetPort.cpp similarity index 100% rename from src/interface/HilsInOut/Ports/HilsI2cTargetPort.cpp rename to src/interface/hils/Ports/HilsI2cTargetPort.cpp diff --git a/src/interface/HilsInOut/Ports/HilsI2cTargetPort.h b/src/interface/hils/Ports/HilsI2cTargetPort.h similarity index 100% rename from src/interface/HilsInOut/Ports/HilsI2cTargetPort.h rename to src/interface/hils/Ports/HilsI2cTargetPort.h diff --git a/src/interface/HilsInOut/Ports/HilsUartPort.cpp b/src/interface/hils/Ports/HilsUartPort.cpp similarity index 100% rename from src/interface/HilsInOut/Ports/HilsUartPort.cpp rename to src/interface/hils/Ports/HilsUartPort.cpp diff --git a/src/interface/HilsInOut/Ports/HilsUartPort.h b/src/interface/hils/Ports/HilsUartPort.h similarity index 100% rename from src/interface/HilsInOut/Ports/HilsUartPort.h rename to src/interface/hils/Ports/HilsUartPort.h diff --git a/src/s2e.cpp b/src/s2e.cpp index 93048aa20..4d0b58af1 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -20,8 +20,8 @@ // Add custom include files #include "simulation/case/sample_case.hpp" // #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" -// #include "interface/HilsInOut/COSMOSWrapper.h" -// #include "interface/HilsInOut/HardwareMessage.h" +// #include "interface/hils/COSMOSWrapper.h" +// #include "interface/hils/HardwareMessage.h" void print_path(std::string path) { #ifdef WIN32 diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 8607d6163..63cf0e5d4 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include From ad5927784fc79104dd2372c18671a77d28013117 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 09:56:14 +0100 Subject: [PATCH 0261/1086] Rename Ports directory --- src/interface/hils/CMakeLists.txt | 4 ++-- src/interface/hils/HilsPortManager.h | 4 ++-- src/interface/hils/{Ports => ports}/HilsI2cTargetPort.cpp | 0 src/interface/hils/{Ports => ports}/HilsI2cTargetPort.h | 0 src/interface/hils/{Ports => ports}/HilsUartPort.cpp | 0 src/interface/hils/{Ports => ports}/HilsUartPort.h | 0 6 files changed, 4 insertions(+), 4 deletions(-) rename src/interface/hils/{Ports => ports}/HilsI2cTargetPort.cpp (100%) rename src/interface/hils/{Ports => ports}/HilsI2cTargetPort.h (100%) rename src/interface/hils/{Ports => ports}/HilsUartPort.cpp (100%) rename src/interface/hils/{Ports => ports}/HilsUartPort.h (100%) diff --git a/src/interface/hils/CMakeLists.txt b/src/interface/hils/CMakeLists.txt index a2ce3d0e8..1356a8f19 100644 --- a/src/interface/hils/CMakeLists.txt +++ b/src/interface/hils/CMakeLists.txt @@ -4,8 +4,8 @@ cmake_minimum_required(VERSION 3.13) if(USE_HILS) add_library(${PROJECT_NAME} STATIC HilsPortManager.cpp - Ports/HilsUartPort.cpp - Ports/HilsI2cTargetPort.cpp + ports/HilsUartPort.cpp + ports/HilsI2cTargetPort.cpp ) else() add_library(${PROJECT_NAME} STATIC diff --git a/src/interface/hils/HilsPortManager.h b/src/interface/hils/HilsPortManager.h index a723b5ff5..e9a55fe63 100644 --- a/src/interface/hils/HilsPortManager.h +++ b/src/interface/hils/HilsPortManager.h @@ -5,8 +5,8 @@ #pragma once #ifdef USE_HILS -#include "Ports/HilsI2cTargetPort.h" -#include "Ports/HilsUartPort.h" +#include "ports/HilsI2cTargetPort.h" +#include "ports/HilsUartPort.h" #endif #include diff --git a/src/interface/hils/Ports/HilsI2cTargetPort.cpp b/src/interface/hils/ports/HilsI2cTargetPort.cpp similarity index 100% rename from src/interface/hils/Ports/HilsI2cTargetPort.cpp rename to src/interface/hils/ports/HilsI2cTargetPort.cpp diff --git a/src/interface/hils/Ports/HilsI2cTargetPort.h b/src/interface/hils/ports/HilsI2cTargetPort.h similarity index 100% rename from src/interface/hils/Ports/HilsI2cTargetPort.h rename to src/interface/hils/ports/HilsI2cTargetPort.h diff --git a/src/interface/hils/Ports/HilsUartPort.cpp b/src/interface/hils/ports/HilsUartPort.cpp similarity index 100% rename from src/interface/hils/Ports/HilsUartPort.cpp rename to src/interface/hils/ports/HilsUartPort.cpp diff --git a/src/interface/hils/Ports/HilsUartPort.h b/src/interface/hils/ports/HilsUartPort.h similarity index 100% rename from src/interface/hils/Ports/HilsUartPort.h rename to src/interface/hils/ports/HilsUartPort.h From d652c32f00c062f70285590017a22ea41eabc381 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 09:58:52 +0100 Subject: [PATCH 0262/1086] Rename HilsI2cTargetPort --- src/interface/hils/CMakeLists.txt | 2 +- src/interface/hils/HilsPortManager.h | 2 +- .../{HilsI2cTargetPort.cpp => hils_i2c_target_port.cpp} | 4 ++-- .../{HilsI2cTargetPort.h => hils_i2c_target_port.hpp} | 8 ++++++-- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/interface/hils/ports/{HilsI2cTargetPort.cpp => hils_i2c_target_port.cpp} (98%) rename src/interface/hils/ports/{HilsI2cTargetPort.h => hils_i2c_target_port.hpp} (94%) diff --git a/src/interface/hils/CMakeLists.txt b/src/interface/hils/CMakeLists.txt index 1356a8f19..8b27ebfad 100644 --- a/src/interface/hils/CMakeLists.txt +++ b/src/interface/hils/CMakeLists.txt @@ -5,7 +5,7 @@ if(USE_HILS) add_library(${PROJECT_NAME} STATIC HilsPortManager.cpp ports/HilsUartPort.cpp - ports/HilsI2cTargetPort.cpp + ports/hils_i2c_target_port.cpp ) else() add_library(${PROJECT_NAME} STATIC diff --git a/src/interface/hils/HilsPortManager.h b/src/interface/hils/HilsPortManager.h index e9a55fe63..ab4cbefa7 100644 --- a/src/interface/hils/HilsPortManager.h +++ b/src/interface/hils/HilsPortManager.h @@ -5,7 +5,7 @@ #pragma once #ifdef USE_HILS -#include "ports/HilsI2cTargetPort.h" +#include "ports/hils_i2c_target_port.hpp" #include "ports/HilsUartPort.h" #endif #include diff --git a/src/interface/hils/ports/HilsI2cTargetPort.cpp b/src/interface/hils/ports/hils_i2c_target_port.cpp similarity index 98% rename from src/interface/hils/ports/HilsI2cTargetPort.cpp rename to src/interface/hils/ports/hils_i2c_target_port.cpp index 29079bdb7..52f8ba868 100644 --- a/src/interface/hils/ports/HilsI2cTargetPort.cpp +++ b/src/interface/hils/ports/hils_i2c_target_port.cpp @@ -1,9 +1,9 @@ /** - * @file HilsI2cTargetPort.cpp + * @file hils_i2c_target_port.cpp * @brief Class to control I2C-USB converter for the target(device) side from COM port */ -#include "HilsI2cTargetPort.h" +#include "hils_i2c_target_port.hpp" // #define HILS_I2C_TARGET_PORT_SHOW_DEBUG_DATA //!< Remove comment when you want to show the debug message diff --git a/src/interface/hils/ports/HilsI2cTargetPort.h b/src/interface/hils/ports/hils_i2c_target_port.hpp similarity index 94% rename from src/interface/hils/ports/HilsI2cTargetPort.h rename to src/interface/hils/ports/hils_i2c_target_port.hpp index 7edbdb045..97dbd14fa 100644 --- a/src/interface/hils/ports/HilsI2cTargetPort.h +++ b/src/interface/hils/ports/hils_i2c_target_port.hpp @@ -1,9 +1,11 @@ /** - * @file HilsI2cTargetPort.h + * @file hils_i2c_target_port.hpp * @brief Class to control I2C-USB converter for the target(device) side from COM port */ -#pragma once +#ifndef S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ +#define S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ + #include #include "HilsUartPort.h" @@ -104,3 +106,5 @@ class HilsI2cTargetPort : public HilsUartPort { /** @brief Buffer for the command from COM port : **/ std::map cmd_buffer_; }; + +#endif // S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ From dd43e7de00f83d51ad3897c034f9cce67b5e0f9b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:00:55 +0100 Subject: [PATCH 0263/1086] Rename HilsUartPort --- src/interface/hils/CMakeLists.txt | 2 +- src/interface/hils/HilsPortManager.h | 2 +- src/interface/hils/ports/hils_i2c_target_port.hpp | 2 +- .../hils/ports/{HilsUartPort.cpp => hils_uart_port.cpp} | 4 ++-- .../hils/ports/{HilsUartPort.h => hils_uart_port.hpp} | 8 ++++++-- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/interface/hils/ports/{HilsUartPort.cpp => hils_uart_port.cpp} (98%) rename src/interface/hils/ports/{HilsUartPort.h => hils_uart_port.hpp} (94%) diff --git a/src/interface/hils/CMakeLists.txt b/src/interface/hils/CMakeLists.txt index 8b27ebfad..d88dd551b 100644 --- a/src/interface/hils/CMakeLists.txt +++ b/src/interface/hils/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) if(USE_HILS) add_library(${PROJECT_NAME} STATIC HilsPortManager.cpp - ports/HilsUartPort.cpp + ports/hils_uart_port.cpp ports/hils_i2c_target_port.cpp ) else() diff --git a/src/interface/hils/HilsPortManager.h b/src/interface/hils/HilsPortManager.h index ab4cbefa7..72159dd60 100644 --- a/src/interface/hils/HilsPortManager.h +++ b/src/interface/hils/HilsPortManager.h @@ -6,7 +6,7 @@ #pragma once #ifdef USE_HILS #include "ports/hils_i2c_target_port.hpp" -#include "ports/HilsUartPort.h" +#include "ports/hils_uart_port.hpp" #endif #include diff --git a/src/interface/hils/ports/hils_i2c_target_port.hpp b/src/interface/hils/ports/hils_i2c_target_port.hpp index 97dbd14fa..b00687363 100644 --- a/src/interface/hils/ports/hils_i2c_target_port.hpp +++ b/src/interface/hils/ports/hils_i2c_target_port.hpp @@ -8,7 +8,7 @@ #include -#include "HilsUartPort.h" +#include "hils_uart_port.hpp" const int kDefaultCmdSize = 0xff; //!< Default command size const int kDefaultTxSize = 0xff; //!< Default TX size diff --git a/src/interface/hils/ports/HilsUartPort.cpp b/src/interface/hils/ports/hils_uart_port.cpp similarity index 98% rename from src/interface/hils/ports/HilsUartPort.cpp rename to src/interface/hils/ports/hils_uart_port.cpp index d7bd73896..2d6ff4d1d 100644 --- a/src/interface/hils/ports/HilsUartPort.cpp +++ b/src/interface/hils/ports/hils_uart_port.cpp @@ -1,12 +1,12 @@ /** - * @file HilsUartPort.h + * @file hils_uart_port.cpp * @brief Class to manage PC's COM port * @details Currently, this feature supports Windows Visual Studio only.(FIXME) * Reference: https://docs.microsoft.com/en-us/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 * @note TODO :We need to clarify the difference with ComPortInterface */ -#include "HilsUartPort.h" +#include "hils_uart_port.hpp" // # define HILS_UART_PORT_SHOW_DEBUG_DATA diff --git a/src/interface/hils/ports/HilsUartPort.h b/src/interface/hils/ports/hils_uart_port.hpp similarity index 94% rename from src/interface/hils/ports/HilsUartPort.h rename to src/interface/hils/ports/hils_uart_port.hpp index 46cbd0f1f..0981486b9 100644 --- a/src/interface/hils/ports/HilsUartPort.h +++ b/src/interface/hils/ports/hils_uart_port.hpp @@ -1,12 +1,14 @@ /** - * @file HilsUartPort.h + * @file hils_uart_port.hpp * @brief Class to manage PC's COM port * @details Currently, this feature supports Windows Visual Studio only.(FIXME) * Reference: https://docs.microsoft.com/en-us/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 * @note TODO :We need to clarify the difference with ComPortInterface */ -#pragma once +#ifndef S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ +#define S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ + #include #include @@ -108,3 +110,5 @@ class HilsUartPort { */ int DiscardOutBuffer(); }; + +#endif // S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ From ec545a9d8c67c3b91855ce22116e8571aef5e9fc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:04:43 +0100 Subject: [PATCH 0264/1086] Rename ComPortInterface --- src/interface/hils/HardwareMessage.h | 2 +- .../hils/{ComPortInterface.cpp => com_port_interface.cpp} | 4 ++-- .../hils/{ComPortInterface.h => com_port_interface.hpp} | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) rename src/interface/hils/{ComPortInterface.cpp => com_port_interface.cpp} (97%) rename src/interface/hils/{ComPortInterface.h => com_port_interface.hpp} (94%) diff --git a/src/interface/hils/HardwareMessage.h b/src/interface/hils/HardwareMessage.h index 5cde7e360..57090a567 100644 --- a/src/interface/hils/HardwareMessage.h +++ b/src/interface/hils/HardwareMessage.h @@ -10,7 +10,7 @@ #include #include "../log_output/loggable.hpp" -#include "ComPortInterface.h" +#include "com_port_interface.hpp" typedef unsigned short int crc_t; diff --git a/src/interface/hils/ComPortInterface.cpp b/src/interface/hils/com_port_interface.cpp similarity index 97% rename from src/interface/hils/ComPortInterface.cpp rename to src/interface/hils/com_port_interface.cpp index af5bc4876..ab15eb3ab 100644 --- a/src/interface/hils/ComPortInterface.cpp +++ b/src/interface/hils/com_port_interface.cpp @@ -1,11 +1,11 @@ /** - * @file ComPortInterface.cpp + * @file com_port_interface.cpp * @brief Class to manage PC's COM port * @details Currently, this feature supports Windows Visual Studio only.(FIXME) * Reference: https://docs.microsoft.com/ja-jp/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 */ -#include "ComPortInterface.h" +#include "com_port_interface.hpp" ComPortInterface::ComPortInterface(int port_id, int baudrate, unsigned int tx_buffer_size, unsigned int rx_buffer_size) : kPortId(port_id), kPortName(PortName(port_id)), kBaudRate(baudrate), kTxBufferSize(tx_buffer_size), kRxBufferSize(rx_buffer_size) { diff --git a/src/interface/hils/ComPortInterface.h b/src/interface/hils/com_port_interface.hpp similarity index 94% rename from src/interface/hils/ComPortInterface.h rename to src/interface/hils/com_port_interface.hpp index 8d5ae0b2f..afeaf5401 100644 --- a/src/interface/hils/ComPortInterface.h +++ b/src/interface/hils/com_port_interface.hpp @@ -1,11 +1,13 @@ /** - * @file ComPortInterface.h + * @file com_port_interface.hpp * @brief Class to manage PC's COM port * @details Currently, this feature supports Windows Visual Studio only.(FIXME) * Reference: https://docs.microsoft.com/ja-jp/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 */ -#pragma once +#ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ +#define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ + #include #include #include @@ -101,3 +103,5 @@ class ComPortInterface { msclr::gcroot tx_buf_; //!< TX Buffer msclr::gcroot rx_buf_; //!< RX Buffer }; + +#endif // S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ From 2a2f2a30b55be83a0f1b8b39c51448a099ac57a9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:05:46 +0100 Subject: [PATCH 0265/1086] Delete HardwareMessage --- src/interface/hils/HardwareMessage.cpp | 206 ------------------------- src/interface/hils/HardwareMessage.h | 87 ----------- 2 files changed, 293 deletions(-) delete mode 100644 src/interface/hils/HardwareMessage.cpp delete mode 100644 src/interface/hils/HardwareMessage.h diff --git a/src/interface/hils/HardwareMessage.cpp b/src/interface/hils/HardwareMessage.cpp deleted file mode 100644 index ff78b9cc6..000000000 --- a/src/interface/hils/HardwareMessage.cpp +++ /dev/null @@ -1,206 +0,0 @@ -/** - * @file HardwareMessage.cpp - * @brief An example of communication class for HILS - * @note This file is very old and recently not managed well... - * TODO: Add detailed comment... or Delete this file from s2e-core since this is user side code. - */ - -#include "HardwareMessage.h" - -HardwareMessage::HardwareMessage(int port_id, bool enable, unsigned int baudrate, unsigned int obc_com_period) - : enable_(enable), obc_com_period_(obc_com_period), kBaudRate(baudrate) { - hils_com_port_ = new ComPortInterface(port_id, kBaudRate, kTxMessageSize, kRxMessageSize); - // IsLogEnabled = true; // InitHardwareMessage.cpp内で設定 - ZeroPad(txbuff, sizeof(txbuff)); - ZeroPad(rxbuff, sizeof(rxbuff)); - ZeroPad(&hw_msg_, sizeof(hw_msg_)); -} - -HardwareMessage::HardwareMessage() : enable_(false), kBaudRate(0) {} - -HardwareMessage::~HardwareMessage() { delete hils_com_port_; } - -int HardwareMessage::Initialize() { - if (!enable_) return -1; - - int ret = hils_com_port_->Initialize(); - if (ret == -1) { - // ポート初期設定失敗 - // printf((hw_msg->hils_com_port->kPortName + - // "の初期設定に失敗しました。").c_str()); - printf("COMポートの初期設定に失敗しました。"); - } else if (ret < -1) { - // ポートOPEN失敗 - // printf((hw_msg->hils_com_port->kPortName + - // "のOPENに失敗しました。").c_str()); - printf("COMポートのOPENに失敗しました。"); - } - // printf((hw_msg->hils_com_port->kPortName + - // "のOPENに成功しました。\n").c_str()); - printf("COMポートのOPENに成功しました。"); - - return 0; -} - -int HardwareMessage::ReceiveAndInterpretMsg() { - if (!enable_) return -1; - - int bytes2read = hils_com_port_->BytesToRead(); - // printf("Bytes to read: %d\r", bytes2read); - if (bytes2read < (int)kRxMessageSize) { - // まだメッセージサイズ分のデータが受信バッファに蓄積されていない - return -1; - } - - int offset = 0; - - // メッセージサイズ分読み込み - int received_bytes = hils_com_port_->Receive(rxbuff, offset, kRxMessageSize); - // ヘッダーが一致するまでポインタを移動 - while (memcmp(rxbuff + offset, kHeader, kHeaderSize)) { - if (offset >= kRxMessageSize - kHeaderSize) return -1; // ヘッダー見つからなかった - offset++; - } - // ヘッダーが見つかった。 - // メッセージの全体を取得するため、offset bytes分さらに読み込む。 - if (offset != 0) hils_com_port_->Receive(rxbuff, kRxMessageSize, offset); - - // Buffer内に残ったデータを破棄(常に最新のデータを読むため) - // if (hils_com_port_->DiscardInBuffer() != 0) return -1; - - uint8_t* msg_ptr = rxbuff + offset; // メッセージの開始ポインタ - - // フッターチェック - uint8_t* footer_ptr = msg_ptr + kRxMessageSize - kFooterSize; - if (memcmp(footer_ptr, kFooter, kFooterSize)) return -1; - - // TODO: CRCチェック - uint8_t* crc_ptr = footer_ptr - sizeof(crc_t); - - uint8_t* ptr = msg_ptr; - size_t size; - - // Header - size = sizeof(hw_msg_.header); - memcpy(&(hw_msg_.header), ptr, size); - ptr += size; - - // OBC TI - size = sizeof(hw_msg_.obc_ti); - endian_memcpy(&(hw_msg_.obc_ti), ptr, size); - ptr += size; - printf("\rOBC TI: %d\n", hw_msg_.obc_ti); // for debug - - // SADA - size = sizeof(hw_msg_.sada.limit_switch_status); - endian_memcpy(&(hw_msg_.sada.limit_switch_status), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.position_steps); - endian_memcpy(&(hw_msg_.sada.position_steps), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.position_degrees); - endian_memcpy(&(hw_msg_.sada.position_degrees), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.step_period); - endian_memcpy(&(hw_msg_.sada.step_period), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.steps_remaining); - endian_memcpy(&(hw_msg_.sada.steps_remaining), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.steps_performed); - endian_memcpy(&(hw_msg_.sada.steps_performed), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.steps_since_home); - endian_memcpy(&(hw_msg_.sada.steps_since_home), ptr, size); - ptr += size; - - size = sizeof(hw_msg_.sada.spare); - memcpy(&(hw_msg_.sada.spare), ptr, size); - ptr += size; - - // Valve control - size = sizeof(hw_msg_.valve_ctrl.TV_idx); - endian_memcpy(&(hw_msg_.valve_ctrl.TV_idx), ptr, size); - ptr += size; - printf("\rTV_idx: %d\n", hw_msg_.valve_ctrl.TV_idx); - - size = sizeof(hw_msg_.valve_ctrl.cumulative_rv_open_counter); - endian_memcpy(&(hw_msg_.valve_ctrl.cumulative_rv_open_counter), ptr, size); - ptr += size; - printf("\rcumulative_rv_open_counter: %d\n", hw_msg_.valve_ctrl.cumulative_rv_open_counter); - - printf("thrust [mN]: "); - for (int i = 0; i < VALVE_THRUSTER_MAX; i++) { - size = sizeof(hw_msg_.valve_ctrl.thruster_thrust[i]); - endian_memcpy(&(hw_msg_.valve_ctrl.thruster_thrust[i]), ptr, size); - ptr += size; - printf("%f\t", hw_msg_.valve_ctrl.thruster_thrust[i]); - } - printf("\n"); - - size = sizeof(hw_msg_.valve_ctrl.spare); - memcpy(&(hw_msg_.valve_ctrl.spare), ptr, size); - ptr += size; - - // Thermal control - size = sizeof(hw_msg_.thermal_ctrl.spare); - memcpy(&(hw_msg_.thermal_ctrl.spare), ptr, size); - ptr += size; - - // Spare - size = sizeof(hw_msg_.spare); - memcpy(&(hw_msg_.spare), ptr, size); - ptr += size; - - // CRC - size = sizeof(hw_msg_.crc); - endian_memcpy(&(hw_msg_.crc), ptr, size); - ptr += size; // memcpyではない? - - // Footer - size = sizeof(hw_msg_.footer); - memcpy(&(hw_msg_.footer), ptr, size); - ptr += size; - - return 0; -} - -bool HardwareMessage::Enable() const { return enable_; } - -string HardwareMessage::GetLogHeader() const { - string str_tmp = ""; - // str_tmp += WriteVector("q_t_i2b", "tar", "-", 4); - str_tmp += WriteScalar("OBC_TI"); - str_tmp += WriteScalar("Valve_TV_idx"); - for (int i = 0; i < VALVE_THRUSTER_MAX; i++) { - str_tmp += WriteScalar("Thrust_" + to_string(i) + "[mN]"); - } - - return str_tmp; -} - -string HardwareMessage::GetLogValue() const { - string str_tmp = ""; - - str_tmp += WriteScalar(hw_msg_.obc_ti); - str_tmp += WriteScalar((unsigned int)hw_msg_.valve_ctrl.TV_idx); - for (int i = 0; i < VALVE_THRUSTER_MAX; i++) { - str_tmp += WriteScalar(hw_msg_.valve_ctrl.thruster_thrust[i]); - } - return str_tmp; -} - -void HardwareMessage::ZeroPad(void* ptr, size_t size) { - // ptrからsizeバイトを0埋めする。 - uint8_t* p = (uint8_t*)ptr; - - for (int i = 0; i < size; i++) { - *(p + i) = 0; - } -} diff --git a/src/interface/hils/HardwareMessage.h b/src/interface/hils/HardwareMessage.h deleted file mode 100644 index 57090a567..000000000 --- a/src/interface/hils/HardwareMessage.h +++ /dev/null @@ -1,87 +0,0 @@ -/** - * @file HardwareMessage.h - * @brief An example of communication class for HILS - * @note This file is very old and recently not managed well... - * TODO: Add detailed comment... or Delete this file from s2e-core since this is user side code. - */ - -#pragma once - -#include - -#include "../log_output/loggable.hpp" -#include "com_port_interface.hpp" - -typedef unsigned short int crc_t; - -// 以下のenumはC2AのValveControl.hと整合性をとる -typedef enum { - VALVE_THRUSTER_DVT1, // 0 - VALVE_THRUSTER_DVT2, // 1 - VALVE_THRUSTER_RCT1, // 2 - VALVE_THRUSTER_RCT2, // 3 - VALVE_THRUSTER_RCT3, // 4 - VALVE_THRUSTER_RCT4, // 5 - VALVE_THRUSTER_MAX -} VALVE_THRUSTER_ENUM; - -class HardwareMessage : public ILoggable { - public: - HardwareMessage(int port_id, bool enable, unsigned int baudrate, unsigned int obc_com_period = 1); - HardwareMessage(); // when not in use - ~HardwareMessage(); - int ReceiveAndInterpretMsg(); - // HWMSG* hw_msg; // ここに書くとHWMSGが未定義になる - virtual string GetLogHeader() const; - virtual string GetLogValue() const; - - private: - ComPortInterface* hils_com_port_; - const bool enable_; - unsigned int obc_com_period_; - const int kBaudRate; - static const unsigned int kTxMessageSize = 1; // 基本送らない - static const unsigned int kRxMessageSize = 256; - static const size_t kHeaderSize = 2; - static const size_t kFooterSize = 2; - const uint8_t kHeader[kHeaderSize] = {0xBE, 0xEF}; - const uint8_t kFooter[kFooterSize] = {0xCA, 0xFE}; - uint8_t txbuff[kTxMessageSize]; - uint8_t rxbuff[kRxMessageSize * 2]; // HACK: - // ヘッダーが見つからない場合のため、とりあえず2倍用意しておく - - static void ZeroPad(void* ptr, size_t size); - - struct HWMSG { - uint8_t header[kHeaderSize]; - uint32_t obc_ti; - struct SADA { - uint8_t limit_switch_status; - int32_t position_steps; - int16_t position_degrees; - uint16_t step_period; - uint32_t steps_remaining; - uint64_t steps_performed; - uint64_t steps_since_home; - uint8_t spare[3]; - } sada; - struct VALVE_CTRL { - uint8_t TV_idx; - uint32_t cumulative_rv_open_counter; - double thruster_thrust[VALVE_THRUSTER_MAX]; - uint8_t spare[11]; - } valve_ctrl; - struct THERMAL_CTRL { - uint8_t spare[64]; - } thermal_ctrl; - uint8_t spare[86]; - crc_t crc; - uint8_t footer[kFooterSize]; - } hw_msg_; - - public: - const HWMSG* hw_msg = &hw_msg_; // これで外部から書き換え禁止のアクセスできるか? - const ComPortInterface* hils_com_port = hils_com_port_; - bool Enable() const; - int Initialize(); -}; From b880a69ebd74c0217db0a4393f3ec052600b47ef Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:07:24 +0100 Subject: [PATCH 0266/1086] Delete Unmanaged Init files --- src/interface/hils/InitCosmosWrapper.cpp | 26 ---------------------- src/interface/hils/InitHardwareMessage.cpp | 26 ---------------------- 2 files changed, 52 deletions(-) delete mode 100644 src/interface/hils/InitCosmosWrapper.cpp delete mode 100644 src/interface/hils/InitHardwareMessage.cpp diff --git a/src/interface/hils/InitCosmosWrapper.cpp b/src/interface/hils/InitCosmosWrapper.cpp deleted file mode 100644 index 5ca2e451d..000000000 --- a/src/interface/hils/InitCosmosWrapper.cpp +++ /dev/null @@ -1,26 +0,0 @@ -/** - * @file InitCosmosWrapper.cpp - * @brief Initialize function for COSMOSWrapper - */ - -#include "../hils/COSMOSWrapper.h" -#include "Initialize.h" - -/** - * @fn Init_COSMOSWrapper - * @brief Initialize function for COSMOSWrapper - * @param [in] file_name: File nama of the initialize file - */ -COSMOSWrapper* Init_COSMOSWrapper(string file_name) { - IniAccess ini_file(file_name); - - char* section = "COSMOS"; - const unsigned int ip_name_len = 16; - char server_ip[ip_name_len]; - bool connect_to_cosmos = ini_file.ReadEnable(section, "ConnectToCosmos"); - unsigned short cosmos_tcp_port_num = ini_file.ReadInt(section, "TCPPortNum"); - ini_file.ReadChar(section, "ServerIP", ip_name_len, server_ip); - - COSMOSWrapper* cosmos_wrapper = new COSMOSWrapper(cosmos_tcp_port_num, connect_to_cosmos, server_ip); - return cosmos_wrapper; -} \ No newline at end of file diff --git a/src/interface/hils/InitHardwareMessage.cpp b/src/interface/hils/InitHardwareMessage.cpp deleted file mode 100644 index 578d2cf6c..000000000 --- a/src/interface/hils/InitHardwareMessage.cpp +++ /dev/null @@ -1,26 +0,0 @@ -/** - * @file InitHardwareMessage.cpp - * @brief Initialize function for HardwareMessage - */ - -#include "../hils/HardwareMessage.h" -#include "Initialize.h" - -/** - * @fn Init_HardwareMessage - * @brief Initialize function for HardwareMessage - * @param [in] file_name: File nama of the initialize file - */ -HardwareMessage* Init_HardwareMessage(string file_name) { - IniAccess ini_file(file_name); - - char* section = "ObcDebugCom"; - bool receive_msg_from_obc = ini_file.ReadEnable(section, "ReceiveMsgFromObc"); - unsigned int obc_com_period = ini_file.ReadInt(section, "ObcComPeriod"); - unsigned int baudrate = ini_file.ReadInt(section, "BaudRate"); - unsigned short obc_com_port_num = ini_file.ReadInt(section, "ComPortNum"); - - HardwareMessage* hw_msg = new HardwareMessage(obc_com_port_num, receive_msg_from_obc, baudrate, obc_com_period); - hw_msg->IsLogEnabled = receive_msg_from_obc; - return hw_msg; -} \ No newline at end of file From e48c1ff4ceccda0dbcad49a1e9504b31d7500897 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:10:17 +0100 Subject: [PATCH 0267/1086] Rename HilsPortManager --- src/Component/Abstract/I2cControllerCommunicationBase.h | 2 +- src/Component/Abstract/ObcCommunicationBase.h | 2 +- src/Component/Abstract/ObcI2cTargetCommunicationBase.h | 2 +- src/interface/hils/CMakeLists.txt | 4 ++-- .../hils/{HilsPortManager.cpp => hils_port_manager.cpp} | 4 ++-- .../hils/{HilsPortManager.h => hils_port_manager.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 7 files changed, 14 insertions(+), 10 deletions(-) rename src/interface/hils/{HilsPortManager.cpp => hils_port_manager.cpp} (98%) rename src/interface/hils/{HilsPortManager.h => hils_port_manager.hpp} (96%) diff --git a/src/Component/Abstract/I2cControllerCommunicationBase.h b/src/Component/Abstract/I2cControllerCommunicationBase.h index e687f1fa9..7953134ed 100644 --- a/src/Component/Abstract/I2cControllerCommunicationBase.h +++ b/src/Component/Abstract/I2cControllerCommunicationBase.h @@ -3,7 +3,7 @@ * @brief This class simulates the I2C Controller communication with the I2C Target. */ #pragma once -#include "../../interface/hils/HilsPortManager.h" +#include "../../interface/hils/hils_port_manager.hpp" #include "ObcCommunicationBase.h" /** diff --git a/src/Component/Abstract/ObcCommunicationBase.h b/src/Component/Abstract/ObcCommunicationBase.h index ee8466583..b739feea3 100644 --- a/src/Component/Abstract/ObcCommunicationBase.h +++ b/src/Component/Abstract/ObcCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for serial communication (e.g., UART) with OBC flight software */ #pragma once -#include +#include #include "../CDH/OBC.h" diff --git a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h index d8df6ab66..69888329a 100644 --- a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h +++ b/src/Component/Abstract/ObcI2cTargetCommunicationBase.h @@ -3,7 +3,7 @@ * @brief Base class for I2C communication as target side with OBC flight software */ #pragma once -#include "../../interface/hils/HilsPortManager.h" +#include "../../interface/hils/hils_port_manager.hpp" #include "../CDH/OBC.h" #include "ObcCommunicationBase.h" diff --git a/src/interface/hils/CMakeLists.txt b/src/interface/hils/CMakeLists.txt index d88dd551b..66e6ff4e9 100644 --- a/src/interface/hils/CMakeLists.txt +++ b/src/interface/hils/CMakeLists.txt @@ -3,13 +3,13 @@ cmake_minimum_required(VERSION 3.13) if(USE_HILS) add_library(${PROJECT_NAME} STATIC - HilsPortManager.cpp + hils_port_manager.cpp ports/hils_uart_port.cpp ports/hils_i2c_target_port.cpp ) else() add_library(${PROJECT_NAME} STATIC - HilsPortManager.cpp + hils_port_manager.cpp ) endif() diff --git a/src/interface/hils/HilsPortManager.cpp b/src/interface/hils/hils_port_manager.cpp similarity index 98% rename from src/interface/hils/HilsPortManager.cpp rename to src/interface/hils/hils_port_manager.cpp index fbf1e3291..2dba84e60 100644 --- a/src/interface/hils/HilsPortManager.cpp +++ b/src/interface/hils/hils_port_manager.cpp @@ -1,9 +1,9 @@ /** - * @file HilsPortManager.cpp + * @file hils_port_manager.cpp * @brief Class to manage COM ports for HILS test */ -#include "HilsPortManager.h" +#include "hils_port_manager.hpp" #include diff --git a/src/interface/hils/HilsPortManager.h b/src/interface/hils/hils_port_manager.hpp similarity index 96% rename from src/interface/hils/HilsPortManager.h rename to src/interface/hils/hils_port_manager.hpp index 72159dd60..12aebdb67 100644 --- a/src/interface/hils/HilsPortManager.h +++ b/src/interface/hils/hils_port_manager.hpp @@ -1,9 +1,11 @@ /** - * @file HilsPortManager.h + * @file hils_port_manager.hpp * @brief Class to manage COM ports for HILS test */ -#pragma once +#ifndef S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ +#define S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ + #ifdef USE_HILS #include "ports/hils_i2c_target_port.hpp" #include "ports/hils_uart_port.hpp" @@ -164,3 +166,5 @@ class HilsPortManager { std::map i2c_com_ports_; //!< I2C ports #endif }; + +#endif // S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 63cf0e5d4..34e9963da 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include From 5a55b0076108766fe93d5d3961b757b52cf27401 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:14:44 +0100 Subject: [PATCH 0268/1086] Rename SpacecraftInOut --- CMakeLists.txt | 4 ++-- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/CDH/OBC.h | 6 +++--- src/Component/CDH/OBC_C2A.h | 2 +- src/Component/Power/PCU.h | 2 +- src/interface/{SpacecraftInOut => sils}/CMakeLists.txt | 0 src/interface/{SpacecraftInOut => sils}/Ports/GPIOPort.cpp | 0 src/interface/{SpacecraftInOut => sils}/Ports/GPIOPort.h | 0 src/interface/{SpacecraftInOut => sils}/Ports/I2CPort.cpp | 0 src/interface/{SpacecraftInOut => sils}/Ports/I2CPort.h | 0 src/interface/{SpacecraftInOut => sils}/Ports/PowerPort.cpp | 0 src/interface/{SpacecraftInOut => sils}/Ports/PowerPort.h | 0 src/interface/{SpacecraftInOut => sils}/Ports/SCIPort.cpp | 0 src/interface/{SpacecraftInOut => sils}/Ports/SCIPort.h | 0 .../{SpacecraftInOut => sils}/Utils/ITCTMChannel.h | 0 .../{SpacecraftInOut => sils}/Utils/RingBuffer.cpp | 0 src/interface/{SpacecraftInOut => sils}/Utils/RingBuffer.h | 0 17 files changed, 8 insertions(+), 8 deletions(-) rename src/interface/{SpacecraftInOut => sils}/CMakeLists.txt (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/GPIOPort.cpp (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/GPIOPort.h (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/I2CPort.cpp (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/I2CPort.h (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/PowerPort.cpp (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/PowerPort.h (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/SCIPort.cpp (100%) rename src/interface/{SpacecraftInOut => sils}/Ports/SCIPort.h (100%) rename src/interface/{SpacecraftInOut => sils}/Utils/ITCTMChannel.h (100%) rename src/interface/{SpacecraftInOut => sils}/Utils/RingBuffer.cpp (100%) rename src/interface/{SpacecraftInOut => sils}/Utils/RingBuffer.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 043ffeb78..4621d61ee 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,7 +41,7 @@ if(USE_C2A) add_definitions(-DSILS_FW) #include_directories include_directories(${C2A_DIR}/src) - include_directories(${S2E_CORE_DIR}/src/interface/SpacecraftInOut) + include_directories(${S2E_CORE_DIR}/src/interface/sils) #add subdirectory add_subdirectory(${C2A_DIR} C2A) endif() @@ -72,7 +72,7 @@ add_subdirectory(src/Component) add_subdirectory(src/relative_information) add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/log_output) -add_subdirectory(src/interface/SpacecraftInOut) +add_subdirectory(src/interface/sils) add_subdirectory(src/interface/hils) add_subdirectory(src/Library/igrf) add_subdirectory(src/Library/inih) diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 8a8555b6e..ce2e955f5 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index 6e0b3f801..3ac42d3af 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -3,9 +3,9 @@ * @brief Class to emulate on board computer */ #pragma once -#include -#include -#include +#include +#include +#include #include diff --git a/src/Component/CDH/OBC_C2A.h b/src/Component/CDH/OBC_C2A.h index 21efaa49d..efbbdb3a3 100644 --- a/src/Component/CDH/OBC_C2A.h +++ b/src/Component/CDH/OBC_C2A.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include "OBC.h" diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index fdea4baf7..fb8c65559 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -5,7 +5,7 @@ #pragma once #include -#include +#include #include diff --git a/src/interface/SpacecraftInOut/CMakeLists.txt b/src/interface/sils/CMakeLists.txt similarity index 100% rename from src/interface/SpacecraftInOut/CMakeLists.txt rename to src/interface/sils/CMakeLists.txt diff --git a/src/interface/SpacecraftInOut/Ports/GPIOPort.cpp b/src/interface/sils/Ports/GPIOPort.cpp similarity index 100% rename from src/interface/SpacecraftInOut/Ports/GPIOPort.cpp rename to src/interface/sils/Ports/GPIOPort.cpp diff --git a/src/interface/SpacecraftInOut/Ports/GPIOPort.h b/src/interface/sils/Ports/GPIOPort.h similarity index 100% rename from src/interface/SpacecraftInOut/Ports/GPIOPort.h rename to src/interface/sils/Ports/GPIOPort.h diff --git a/src/interface/SpacecraftInOut/Ports/I2CPort.cpp b/src/interface/sils/Ports/I2CPort.cpp similarity index 100% rename from src/interface/SpacecraftInOut/Ports/I2CPort.cpp rename to src/interface/sils/Ports/I2CPort.cpp diff --git a/src/interface/SpacecraftInOut/Ports/I2CPort.h b/src/interface/sils/Ports/I2CPort.h similarity index 100% rename from src/interface/SpacecraftInOut/Ports/I2CPort.h rename to src/interface/sils/Ports/I2CPort.h diff --git a/src/interface/SpacecraftInOut/Ports/PowerPort.cpp b/src/interface/sils/Ports/PowerPort.cpp similarity index 100% rename from src/interface/SpacecraftInOut/Ports/PowerPort.cpp rename to src/interface/sils/Ports/PowerPort.cpp diff --git a/src/interface/SpacecraftInOut/Ports/PowerPort.h b/src/interface/sils/Ports/PowerPort.h similarity index 100% rename from src/interface/SpacecraftInOut/Ports/PowerPort.h rename to src/interface/sils/Ports/PowerPort.h diff --git a/src/interface/SpacecraftInOut/Ports/SCIPort.cpp b/src/interface/sils/Ports/SCIPort.cpp similarity index 100% rename from src/interface/SpacecraftInOut/Ports/SCIPort.cpp rename to src/interface/sils/Ports/SCIPort.cpp diff --git a/src/interface/SpacecraftInOut/Ports/SCIPort.h b/src/interface/sils/Ports/SCIPort.h similarity index 100% rename from src/interface/SpacecraftInOut/Ports/SCIPort.h rename to src/interface/sils/Ports/SCIPort.h diff --git a/src/interface/SpacecraftInOut/Utils/ITCTMChannel.h b/src/interface/sils/Utils/ITCTMChannel.h similarity index 100% rename from src/interface/SpacecraftInOut/Utils/ITCTMChannel.h rename to src/interface/sils/Utils/ITCTMChannel.h diff --git a/src/interface/SpacecraftInOut/Utils/RingBuffer.cpp b/src/interface/sils/Utils/RingBuffer.cpp similarity index 100% rename from src/interface/SpacecraftInOut/Utils/RingBuffer.cpp rename to src/interface/sils/Utils/RingBuffer.cpp diff --git a/src/interface/SpacecraftInOut/Utils/RingBuffer.h b/src/interface/sils/Utils/RingBuffer.h similarity index 100% rename from src/interface/SpacecraftInOut/Utils/RingBuffer.h rename to src/interface/sils/Utils/RingBuffer.h From e019d42b4fd23de6634630cb7ebb78db78dacf9f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:17:50 +0100 Subject: [PATCH 0269/1086] Rename Ports --- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/CDH/OBC.h | 6 +++--- src/Component/CDH/OBC_C2A.h | 2 +- src/Component/Power/PCU.h | 4 ++-- src/interface/sils/CMakeLists.txt | 8 ++++---- src/interface/sils/{Ports => ports}/GPIOPort.cpp | 0 src/interface/sils/{Ports => ports}/GPIOPort.h | 0 src/interface/sils/{Ports => ports}/I2CPort.cpp | 0 src/interface/sils/{Ports => ports}/I2CPort.h | 0 src/interface/sils/{Ports => ports}/PowerPort.cpp | 0 src/interface/sils/{Ports => ports}/PowerPort.h | 0 src/interface/sils/{Ports => ports}/SCIPort.cpp | 0 src/interface/sils/{Ports => ports}/SCIPort.h | 0 13 files changed, 11 insertions(+), 11 deletions(-) rename src/interface/sils/{Ports => ports}/GPIOPort.cpp (100%) rename src/interface/sils/{Ports => ports}/GPIOPort.h (100%) rename src/interface/sils/{Ports => ports}/I2CPort.cpp (100%) rename src/interface/sils/{Ports => ports}/I2CPort.h (100%) rename src/interface/sils/{Ports => ports}/PowerPort.cpp (100%) rename src/interface/sils/{Ports => ports}/PowerPort.h (100%) rename src/interface/sils/{Ports => ports}/SCIPort.cpp (100%) rename src/interface/sils/{Ports => ports}/SCIPort.h (100%) diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index ce2e955f5..9610f364e 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index 3ac42d3af..92a2945aa 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -3,9 +3,9 @@ * @brief Class to emulate on board computer */ #pragma once -#include -#include -#include +#include +#include +#include #include diff --git a/src/Component/CDH/OBC_C2A.h b/src/Component/CDH/OBC_C2A.h index efbbdb3a3..186fe5b60 100644 --- a/src/Component/CDH/OBC_C2A.h +++ b/src/Component/CDH/OBC_C2A.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include "OBC.h" diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index fb8c65559..275da0742 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -4,9 +4,9 @@ */ #pragma once -#include -#include +#include +#include #include #include "../Abstract/ComponentBase.h" diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index ee6054885..440d7fada 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -2,10 +2,10 @@ project(SC_IO) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Ports/GPIOPort.cpp - Ports/PowerPort.cpp - Ports/SCIPort.cpp - Ports/I2CPort.cpp + ports/GPIOPort.cpp + ports/PowerPort.cpp + ports/SCIPort.cpp + ports/I2CPort.cpp Utils/RingBuffer.cpp ) diff --git a/src/interface/sils/Ports/GPIOPort.cpp b/src/interface/sils/ports/GPIOPort.cpp similarity index 100% rename from src/interface/sils/Ports/GPIOPort.cpp rename to src/interface/sils/ports/GPIOPort.cpp diff --git a/src/interface/sils/Ports/GPIOPort.h b/src/interface/sils/ports/GPIOPort.h similarity index 100% rename from src/interface/sils/Ports/GPIOPort.h rename to src/interface/sils/ports/GPIOPort.h diff --git a/src/interface/sils/Ports/I2CPort.cpp b/src/interface/sils/ports/I2CPort.cpp similarity index 100% rename from src/interface/sils/Ports/I2CPort.cpp rename to src/interface/sils/ports/I2CPort.cpp diff --git a/src/interface/sils/Ports/I2CPort.h b/src/interface/sils/ports/I2CPort.h similarity index 100% rename from src/interface/sils/Ports/I2CPort.h rename to src/interface/sils/ports/I2CPort.h diff --git a/src/interface/sils/Ports/PowerPort.cpp b/src/interface/sils/ports/PowerPort.cpp similarity index 100% rename from src/interface/sils/Ports/PowerPort.cpp rename to src/interface/sils/ports/PowerPort.cpp diff --git a/src/interface/sils/Ports/PowerPort.h b/src/interface/sils/ports/PowerPort.h similarity index 100% rename from src/interface/sils/Ports/PowerPort.h rename to src/interface/sils/ports/PowerPort.h diff --git a/src/interface/sils/Ports/SCIPort.cpp b/src/interface/sils/ports/SCIPort.cpp similarity index 100% rename from src/interface/sils/Ports/SCIPort.cpp rename to src/interface/sils/ports/SCIPort.cpp diff --git a/src/interface/sils/Ports/SCIPort.h b/src/interface/sils/ports/SCIPort.h similarity index 100% rename from src/interface/sils/Ports/SCIPort.h rename to src/interface/sils/ports/SCIPort.h From 5f97a31c3f20207b9e0cbfae9e590700e8f750a6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:19:16 +0100 Subject: [PATCH 0270/1086] Rename Utils --- src/interface/sils/CMakeLists.txt | 2 +- src/interface/sils/ports/SCIPort.h | 2 +- src/interface/sils/{Utils => utility}/ITCTMChannel.h | 0 src/interface/sils/{Utils => utility}/RingBuffer.cpp | 0 src/interface/sils/{Utils => utility}/RingBuffer.h | 0 5 files changed, 2 insertions(+), 2 deletions(-) rename src/interface/sils/{Utils => utility}/ITCTMChannel.h (100%) rename src/interface/sils/{Utils => utility}/RingBuffer.cpp (100%) rename src/interface/sils/{Utils => utility}/RingBuffer.h (100%) diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index 440d7fada..d56d77e01 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC ports/PowerPort.cpp ports/SCIPort.cpp ports/I2CPort.cpp - Utils/RingBuffer.cpp + utility/RingBuffer.cpp ) include(../../../common.cmake) diff --git a/src/interface/sils/ports/SCIPort.h b/src/interface/sils/ports/SCIPort.h index cde580651..95bf50ef5 100644 --- a/src/interface/sils/ports/SCIPort.h +++ b/src/interface/sils/ports/SCIPort.h @@ -4,7 +4,7 @@ */ #pragma once -#include "../Utils/RingBuffer.h" +#include "../utility/RingBuffer.h" /** * @class SCIPort diff --git a/src/interface/sils/Utils/ITCTMChannel.h b/src/interface/sils/utility/ITCTMChannel.h similarity index 100% rename from src/interface/sils/Utils/ITCTMChannel.h rename to src/interface/sils/utility/ITCTMChannel.h diff --git a/src/interface/sils/Utils/RingBuffer.cpp b/src/interface/sils/utility/RingBuffer.cpp similarity index 100% rename from src/interface/sils/Utils/RingBuffer.cpp rename to src/interface/sils/utility/RingBuffer.cpp diff --git a/src/interface/sils/Utils/RingBuffer.h b/src/interface/sils/utility/RingBuffer.h similarity index 100% rename from src/interface/sils/Utils/RingBuffer.h rename to src/interface/sils/utility/RingBuffer.h From 502cd450ad1166d22256b23b40badc07e3363fa7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:22:04 +0100 Subject: [PATCH 0271/1086] Rename GPIOPort --- src/Component/CDH/OBC.h | 2 +- src/Component/CDH/OBC_C2A.h | 2 +- src/interface/sils/CMakeLists.txt | 2 +- src/interface/sils/ports/{GPIOPort.cpp => gpio_port.cpp} | 4 ++-- src/interface/sils/ports/{GPIOPort.h => gpio_port.hpp} | 8 ++++++-- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/interface/sils/ports/{GPIOPort.cpp => gpio_port.cpp} (92%) rename src/interface/sils/ports/{GPIOPort.h => gpio_port.hpp} (86%) diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index 92a2945aa..3d2e14dc3 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -3,7 +3,7 @@ * @brief Class to emulate on board computer */ #pragma once -#include +#include #include #include diff --git a/src/Component/CDH/OBC_C2A.h b/src/Component/CDH/OBC_C2A.h index 186fe5b60..7963aba3f 100644 --- a/src/Component/CDH/OBC_C2A.h +++ b/src/Component/CDH/OBC_C2A.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include "OBC.h" diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index d56d77e01..a3e3deed1 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -2,7 +2,7 @@ project(SC_IO) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - ports/GPIOPort.cpp + ports/gpio_port.cpp ports/PowerPort.cpp ports/SCIPort.cpp ports/I2CPort.cpp diff --git a/src/interface/sils/ports/GPIOPort.cpp b/src/interface/sils/ports/gpio_port.cpp similarity index 92% rename from src/interface/sils/ports/GPIOPort.cpp rename to src/interface/sils/ports/gpio_port.cpp index a3a4b596e..e0eded51d 100644 --- a/src/interface/sils/ports/GPIOPort.cpp +++ b/src/interface/sils/ports/gpio_port.cpp @@ -1,9 +1,9 @@ /** - * @file GPIOPort.cpp + * @file gpio_port.cpp * @brief Class to emulate GPIO(General Purpose Input and Output) port */ -#include "GPIOPort.h" +#include "gpio_port.hpp" GPIOPort::GPIOPort(int port_id, IGPIOCompo* compo) : kPortId(port_id) { hl_state_ = GPIO_LOW; diff --git a/src/interface/sils/ports/GPIOPort.h b/src/interface/sils/ports/gpio_port.hpp similarity index 86% rename from src/interface/sils/ports/GPIOPort.h rename to src/interface/sils/ports/gpio_port.hpp index 61a8bc78f..6b09e8584 100644 --- a/src/interface/sils/ports/GPIOPort.h +++ b/src/interface/sils/ports/gpio_port.hpp @@ -1,9 +1,11 @@ /** - * @file GPIOPort.h + * @file gpio_port.hpp * @brief Class to emulate GPIO(General Purpose Input and Output) port */ -#pragma once +#ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ +#define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ + #include #define GPIO_HIGH true @@ -48,3 +50,5 @@ class GPIOPort { IGPIOCompo* component_; //!< Component which has the GPIO port bool hl_state_; //!< GPIO High/Low state }; + +#endif // S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ From 9a7f0211f2fae3a5220d9ce8ac65fe0111328980 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:24:43 +0100 Subject: [PATCH 0272/1086] Rename I2CPort --- src/Component/CDH/OBC.h | 2 +- src/interface/sils/CMakeLists.txt | 2 +- src/interface/sils/ports/{I2CPort.cpp => i2c_port.cpp} | 7 ++++++- src/interface/sils/ports/{I2CPort.h => i2c_port.hpp} | 8 ++++++-- 4 files changed, 14 insertions(+), 5 deletions(-) rename src/interface/sils/ports/{I2CPort.cpp => i2c_port.cpp} (95%) rename src/interface/sils/ports/{I2CPort.h => i2c_port.hpp} (96%) diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index 3d2e14dc3..9b10255aa 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -4,7 +4,7 @@ */ #pragma once #include -#include +#include #include #include diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index a3e3deed1..335ac9a93 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC ports/gpio_port.cpp ports/PowerPort.cpp ports/SCIPort.cpp - ports/I2CPort.cpp + ports/i2c_port.cpp utility/RingBuffer.cpp ) diff --git a/src/interface/sils/ports/I2CPort.cpp b/src/interface/sils/ports/i2c_port.cpp similarity index 95% rename from src/interface/sils/ports/I2CPort.cpp rename to src/interface/sils/ports/i2c_port.cpp index 999d82a18..af072f4b1 100644 --- a/src/interface/sils/ports/I2CPort.cpp +++ b/src/interface/sils/ports/i2c_port.cpp @@ -1,4 +1,9 @@ -#include "I2CPort.h" +/** + * @file i2c_port.cpp + * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port + */ + +#include "i2c_port.hpp" #include diff --git a/src/interface/sils/ports/I2CPort.h b/src/interface/sils/ports/i2c_port.hpp similarity index 96% rename from src/interface/sils/ports/I2CPort.h rename to src/interface/sils/ports/i2c_port.hpp index 1a2bf83cf..dabe4fc42 100644 --- a/src/interface/sils/ports/I2CPort.h +++ b/src/interface/sils/ports/i2c_port.hpp @@ -1,9 +1,11 @@ /** - * @file I2CPort.h + * @file i2c_port.hpp * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port */ -#pragma once +#ifndef S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ +#define S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ + #include const int kDefaultCmdBufferSize = 0xff; //!< Default command buffer size @@ -106,3 +108,5 @@ class I2CPort { /** @brief Buffer for the command from OBC : **/ std::map, unsigned char> cmd_buffer_; }; + +#endif // S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ From e06964489f15bc6051b6fb80efa3c10ca0d700f4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:26:28 +0100 Subject: [PATCH 0273/1086] Rename PowerPort --- src/Component/Abstract/ComponentBase.h | 2 +- src/Component/Power/PCU.h | 2 +- src/interface/sils/CMakeLists.txt | 2 +- src/interface/sils/ports/{PowerPort.cpp => power_port.cpp} | 4 ++-- src/interface/sils/ports/{PowerPort.h => power_port.hpp} | 7 +++++-- 5 files changed, 10 insertions(+), 7 deletions(-) rename src/interface/sils/ports/{PowerPort.cpp => power_port.cpp} (97%) rename src/interface/sils/ports/{PowerPort.h => power_port.hpp} (96%) diff --git a/src/Component/Abstract/ComponentBase.h b/src/Component/Abstract/ComponentBase.h index 9610f364e..d13da0a09 100644 --- a/src/Component/Abstract/ComponentBase.h +++ b/src/Component/Abstract/ComponentBase.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Power/PCU.h b/src/Component/Power/PCU.h index 275da0742..d0ee1042d 100644 --- a/src/Component/Power/PCU.h +++ b/src/Component/Power/PCU.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index 335ac9a93..a2a6219bc 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC ports/gpio_port.cpp - ports/PowerPort.cpp + ports/power_port.cpp ports/SCIPort.cpp ports/i2c_port.cpp utility/RingBuffer.cpp diff --git a/src/interface/sils/ports/PowerPort.cpp b/src/interface/sils/ports/power_port.cpp similarity index 97% rename from src/interface/sils/ports/PowerPort.cpp rename to src/interface/sils/ports/power_port.cpp index 864d643db..223c264f6 100644 --- a/src/interface/sils/ports/PowerPort.cpp +++ b/src/interface/sils/ports/power_port.cpp @@ -1,9 +1,9 @@ /** - * @file PowerPort.cpp + * @file power_port.cpp * @brief Class to emulate electrical power port */ -#include "PowerPort.h" +#include "power_port.hpp" #include diff --git a/src/interface/sils/ports/PowerPort.h b/src/interface/sils/ports/power_port.hpp similarity index 96% rename from src/interface/sils/ports/PowerPort.h rename to src/interface/sils/ports/power_port.hpp index 686518b2c..6488a9d02 100644 --- a/src/interface/sils/ports/PowerPort.h +++ b/src/interface/sils/ports/power_port.hpp @@ -1,9 +1,10 @@ /** - * @file PowerPort.h + * @file power_port.hpp * @brief Class to emulate electrical power port */ -#pragma once +#ifndef S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ +#define S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ #include @@ -131,3 +132,5 @@ class PowerPort { */ void Initialize(void); }; + +#endif // S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ From 6008b7b1dbe257beac2382532ce046b8fb3e588a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:30:45 +0100 Subject: [PATCH 0274/1086] Rename SCIPort --- src/Component/Abstract/ObcCommunicationBase.h | 2 +- src/Component/CDH/OBC.h | 2 +- src/interface/sils/CMakeLists.txt | 2 +- .../sils/ports/{SCIPort.cpp => uart_port.cpp} | 6 +++--- src/interface/sils/ports/{SCIPort.h => uart_port.hpp} | 10 +++++++--- 5 files changed, 13 insertions(+), 9 deletions(-) rename src/interface/sils/ports/{SCIPort.cpp => uart_port.cpp} (87%) rename src/interface/sils/ports/{SCIPort.h => uart_port.hpp} (91%) diff --git a/src/Component/Abstract/ObcCommunicationBase.h b/src/Component/Abstract/ObcCommunicationBase.h index b739feea3..a3421082b 100644 --- a/src/Component/Abstract/ObcCommunicationBase.h +++ b/src/Component/Abstract/ObcCommunicationBase.h @@ -92,7 +92,7 @@ class ObcCommunicationBase { std::vector rx_buffer_; private: - const int kDefaultBufferSize = 1024; //!< Default buffer size Fixme: The magic number. This is depending on SCIPort.h. + const int kDefaultBufferSize = 1024; //!< Default buffer size Fixme: The magic number. This is depending on uart_port.hpp. int sils_port_id_; //!< Port ID for SILS int hils_port_id_; //!< Port ID for HILS diff --git a/src/Component/CDH/OBC.h b/src/Component/CDH/OBC.h index 9b10255aa..55a58d5f6 100644 --- a/src/Component/CDH/OBC.h +++ b/src/Component/CDH/OBC.h @@ -5,7 +5,7 @@ #pragma once #include #include -#include +#include #include diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index a2a6219bc..5c367bf9d 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC ports/gpio_port.cpp ports/power_port.cpp - ports/SCIPort.cpp + ports/uart_port.cpp ports/i2c_port.cpp utility/RingBuffer.cpp ) diff --git a/src/interface/sils/ports/SCIPort.cpp b/src/interface/sils/ports/uart_port.cpp similarity index 87% rename from src/interface/sils/ports/SCIPort.cpp rename to src/interface/sils/ports/uart_port.cpp index 473d89151..83743ff23 100644 --- a/src/interface/sils/ports/SCIPort.cpp +++ b/src/interface/sils/ports/uart_port.cpp @@ -1,9 +1,9 @@ /** - * @file SCIPort.cpp - * @brief Class to emulate SCI(Serial Communication Interface) communication port + * @file uart_port.cpp + * @brief Class to emulate UART communication port */ -#include "SCIPort.h" +#include "uart_port.hpp" SCIPort::SCIPort() : SCIPort(kDefaultBufferSize, kDefaultBufferSize) {} diff --git a/src/interface/sils/ports/SCIPort.h b/src/interface/sils/ports/uart_port.hpp similarity index 91% rename from src/interface/sils/ports/SCIPort.h rename to src/interface/sils/ports/uart_port.hpp index 95bf50ef5..4f53e39c4 100644 --- a/src/interface/sils/ports/SCIPort.h +++ b/src/interface/sils/ports/uart_port.hpp @@ -1,9 +1,11 @@ /** - * @file SCIPort.h - * @brief Class to emulate SCI(Serial Communication Interface) communication port + * @file uart_port.hpp + * @brief Class to emulate UART communication port */ -#pragma once +#ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ +#define S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ + #include "../utility/RingBuffer.h" /** @@ -76,3 +78,5 @@ class SCIPort { RingBuffer* rxb_; //!< Receive buffer (Component -> OBC) RingBuffer* txb_; //!< Transmit buffer (OBC -> Component) }; + +#endif // S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ From a3f1f023a046ade4dcfe4dab872e3e5c840e2fc2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:32:39 +0100 Subject: [PATCH 0275/1086] Delete unused file --- src/interface/sils/utility/ITCTMChannel.h | 17 ----------------- 1 file changed, 17 deletions(-) delete mode 100644 src/interface/sils/utility/ITCTMChannel.h diff --git a/src/interface/sils/utility/ITCTMChannel.h b/src/interface/sils/utility/ITCTMChannel.h deleted file mode 100644 index 9afcb38c3..000000000 --- a/src/interface/sils/utility/ITCTMChannel.h +++ /dev/null @@ -1,17 +0,0 @@ -/** - * @file ITCTMChannel.h - * @brief - */ - -#pragma once using namespace System; -using namespace System::ServiceModel; - -/** - * @class ITCTMChannel.h - * @brief - */ -[ServiceContract] interface class ITCTMChannel { - [OperationContract] cli::array ^ Cmd_to_SILS(); - - [OperationContract] void Tlm_to_GSTOS(cli::array ^ tlm_buf); -}; From 8e5eb9a7b4f021b0f210064aceae2769d8103b9e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:34:32 +0100 Subject: [PATCH 0276/1086] Rename RingBuffer --- src/interface/sils/CMakeLists.txt | 2 +- src/interface/sils/ports/uart_port.hpp | 2 +- .../sils/utility/{RingBuffer.cpp => ring_buffer.cpp} | 4 ++-- .../sils/utility/{RingBuffer.h => ring_buffer.hpp} | 7 +++++-- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/interface/sils/utility/{RingBuffer.cpp => ring_buffer.cpp} (95%) rename src/interface/sils/utility/{RingBuffer.h => ring_buffer.hpp} (87%) diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt index 5c367bf9d..931d99abc 100644 --- a/src/interface/sils/CMakeLists.txt +++ b/src/interface/sils/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC ports/power_port.cpp ports/uart_port.cpp ports/i2c_port.cpp - utility/RingBuffer.cpp + utility/ring_buffer.cpp ) include(../../../common.cmake) diff --git a/src/interface/sils/ports/uart_port.hpp b/src/interface/sils/ports/uart_port.hpp index 4f53e39c4..f5f012405 100644 --- a/src/interface/sils/ports/uart_port.hpp +++ b/src/interface/sils/ports/uart_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ #define S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ -#include "../utility/RingBuffer.h" +#include "../utility/ring_buffer.hpp" /** * @class SCIPort diff --git a/src/interface/sils/utility/RingBuffer.cpp b/src/interface/sils/utility/ring_buffer.cpp similarity index 95% rename from src/interface/sils/utility/RingBuffer.cpp rename to src/interface/sils/utility/ring_buffer.cpp index a7e9f5e40..764051729 100644 --- a/src/interface/sils/utility/RingBuffer.cpp +++ b/src/interface/sils/utility/ring_buffer.cpp @@ -1,9 +1,9 @@ /** - * @file RingBuffer.cpp + * @file ring_buffer.cpp * @brief Class to emulate ring buffer */ -#include "RingBuffer.h" +#include "ring_buffer.hpp" #include diff --git a/src/interface/sils/utility/RingBuffer.h b/src/interface/sils/utility/ring_buffer.hpp similarity index 87% rename from src/interface/sils/utility/RingBuffer.h rename to src/interface/sils/utility/ring_buffer.hpp index abcdf5139..c98b09ba1 100644 --- a/src/interface/sils/utility/RingBuffer.h +++ b/src/interface/sils/utility/ring_buffer.hpp @@ -1,9 +1,10 @@ /** - * @file RingBuffer.h + * @file ring_buffer.hpp * @brief Class to emulate ring buffer */ -#pragma once +#ifndef S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ +#define S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ typedef unsigned char byte; @@ -50,3 +51,5 @@ class RingBuffer { int rp_; //!< Read pointer int wp_; //!< Write pointer }; + +#endif // S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ From 83ef23d4936ab9f5dae40472de18ce084f53a144 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:42:08 +0100 Subject: [PATCH 0277/1086] Rename Components directory --- CMakeLists.txt | 2 +- .../AOCS/GNSSReceiver.cpp | 0 .../AOCS/GNSSReceiver.h | 0 src/{Component => components}/AOCS/Gyro.cpp | 0 src/{Component => components}/AOCS/Gyro.h | 0 .../AOCS/InitGnssReceiver.cpp | 0 .../AOCS/InitGnssReceiver.hpp | 2 +- .../AOCS/InitGyro.cpp | 0 .../AOCS/InitGyro.hpp | 2 +- .../AOCS/InitMagSensor.cpp | 0 .../AOCS/InitMagSensor.hpp | 2 +- .../AOCS/InitMagTorquer.cpp | 0 .../AOCS/InitMagTorquer.hpp | 2 +- .../AOCS/InitRwModel.cpp | 0 .../AOCS/InitRwModel.hpp | 2 +- .../AOCS/InitStt.cpp | 0 .../AOCS/InitStt.hpp | 2 +- .../AOCS/InitSunSensor.cpp | 0 .../AOCS/InitSunSensor.hpp | 2 +- .../AOCS/MagSensor.cpp | 0 .../AOCS/MagSensor.h | 0 .../AOCS/MagTorquer.cpp | 0 .../AOCS/MagTorquer.h | 0 .../AOCS/RWJitter.cpp | 0 src/{Component => components}/AOCS/RWJitter.h | 0 .../AOCS/RWModel.cpp | 0 src/{Component => components}/AOCS/RWModel.h | 0 src/{Component => components}/AOCS/STT.cpp | 0 src/{Component => components}/AOCS/STT.h | 0 .../AOCS/SunSensor.cpp | 0 .../AOCS/SunSensor.h | 0 src/{Component => components}/AOCS/rw_ode.cpp | 0 src/{Component => components}/AOCS/rw_ode.hpp | 0 .../Abstract/ComponentBase.cpp | 0 .../Abstract/ComponentBase.h | 0 .../I2cControllerCommunicationBase.cpp | 0 .../Abstract/I2cControllerCommunicationBase.h | 0 .../Abstract/IGPIOCompo.h | 0 .../Abstract/ITickable.h | 0 .../Abstract/InitializeSensorBase.hpp | 0 .../Abstract/InitializeSensorBase_tfs.hpp | 0 .../Abstract/ObcCommunicationBase.cpp | 0 .../Abstract/ObcCommunicationBase.h | 0 .../Abstract/ObcGpioBase.cpp | 0 .../Abstract/ObcGpioBase.h | 0 .../ObcI2cTargetCommunicationBase.cpp | 0 .../Abstract/ObcI2cTargetCommunicationBase.h | 0 .../Abstract/SensorBase.h | 0 .../Abstract/SensorBase_tfs.hpp | 0 src/{Component => components}/CDH/OBC.cpp | 0 src/{Component => components}/CDH/OBC.h | 0 src/{Component => components}/CDH/OBC_C2A.cpp | 0 src/{Component => components}/CDH/OBC_C2A.h | 0 src/{Component => components}/CMakeLists.txt | 0 .../CommGS/Antenna.cpp | 0 .../CommGS/Antenna.hpp | 0 .../CommGS/AntennaRadiationPattern.cpp | 0 .../CommGS/AntennaRadiationPattern.hpp | 0 .../CommGS/GScalculator.cpp | 0 .../CommGS/GScalculator.h | 2 +- .../CommGS/InitAntenna.cpp | 0 .../CommGS/InitAntenna.hpp | 2 +- .../CommGS/InitGsCalculator.cpp | 0 .../CommGS/InitGsCalculator.hpp | 2 +- .../IdealComponents/ForceGenerator.cpp | 0 .../IdealComponents/ForceGenerator.hpp | 2 +- .../InitializeForceGenerator.cpp | 0 .../InitializeForceGenerator.hpp | 0 .../InitializeTorqueGenerator.cpp | 0 .../InitializeTorqueGenerator.hpp | 0 .../IdealComponents/TorqueGenerator.cpp | 0 .../IdealComponents/TorqueGenerator.hpp | 2 +- .../Mission/Telescope/InitTelescope.cpp | 0 .../Mission/Telescope/InitTelescope.hpp | 2 +- .../Mission/Telescope/Telescope.cpp | 0 .../Mission/Telescope/Telescope.h | 0 src/{Component => components}/Power/BAT.cpp | 0 src/{Component => components}/Power/BAT.h | 0 .../Power/CsvScenarioInterface.cpp | 0 .../Power/CsvScenarioInterface.h | 0 .../Power/InitBat.cpp | 0 .../Power/InitBat.hpp | 2 +- .../Power/InitPcu_InitialStudy.cpp | 0 .../Power/InitPcu_InitialStudy.hpp | 2 +- .../Power/InitSap.cpp | 0 .../Power/InitSap.hpp | 2 +- src/{Component => components}/Power/PCU.cpp | 0 src/{Component => components}/Power/PCU.h | 0 .../Power/PCU_InitialStudy.cpp | 2 +- .../Power/PCU_InitialStudy.h | 0 src/{Component => components}/Power/SAP.cpp | 2 +- src/{Component => components}/Power/SAP.h | 0 .../Propulsion/InitSimpleThruster.cpp | 0 .../Propulsion/InitSimpleThruster.hpp | 2 +- .../Propulsion/SimpleThruster.cpp | 0 .../Propulsion/SimpleThruster.h | 0 .../Thermal/.gitkeep | 0 .../examples/example_change_structure.cpp | 0 .../examples/example_change_structure.hpp | 0 .../example_i2c_controller_for_hils.cpp | 0 .../example_i2c_controller_for_hils.hpp | 0 .../examples/example_i2c_target_for_hils.cpp | 0 .../examples/example_i2c_target_for_hils.hpp | 0 .../example_serial_communication_for_hils.cpp | 0 .../example_serial_communication_for_hils.hpp | 0 .../example_serial_communication_with_obc.cpp | 0 .../example_serial_communication_with_obc.hpp | 0 src/environment/global/clock_generator.hpp | 2 +- src/interface/hils/com_port_interface.hpp | 2 +- src/interface/sils/ports/gpio_port.hpp | 2 +- .../sample_ground_station.hpp | 4 +-- .../sample_ground_station_components.hpp | 4 +-- .../sample_spacecraft/sample_components.hpp | 34 +++++++++---------- 113 files changed, 44 insertions(+), 44 deletions(-) rename src/{Component => components}/AOCS/GNSSReceiver.cpp (100%) rename src/{Component => components}/AOCS/GNSSReceiver.h (100%) rename src/{Component => components}/AOCS/Gyro.cpp (100%) rename src/{Component => components}/AOCS/Gyro.h (100%) rename src/{Component => components}/AOCS/InitGnssReceiver.cpp (100%) rename src/{Component => components}/AOCS/InitGnssReceiver.hpp (96%) rename src/{Component => components}/AOCS/InitGyro.cpp (100%) rename src/{Component => components}/AOCS/InitGyro.hpp (96%) rename src/{Component => components}/AOCS/InitMagSensor.cpp (100%) rename src/{Component => components}/AOCS/InitMagSensor.hpp (96%) rename src/{Component => components}/AOCS/InitMagTorquer.cpp (100%) rename src/{Component => components}/AOCS/InitMagTorquer.hpp (96%) rename src/{Component => components}/AOCS/InitRwModel.cpp (100%) rename src/{Component => components}/AOCS/InitRwModel.hpp (96%) rename src/{Component => components}/AOCS/InitStt.cpp (100%) rename src/{Component => components}/AOCS/InitStt.hpp (97%) rename src/{Component => components}/AOCS/InitSunSensor.cpp (100%) rename src/{Component => components}/AOCS/InitSunSensor.hpp (96%) rename src/{Component => components}/AOCS/MagSensor.cpp (100%) rename src/{Component => components}/AOCS/MagSensor.h (100%) rename src/{Component => components}/AOCS/MagTorquer.cpp (100%) rename src/{Component => components}/AOCS/MagTorquer.h (100%) rename src/{Component => components}/AOCS/RWJitter.cpp (100%) rename src/{Component => components}/AOCS/RWJitter.h (100%) rename src/{Component => components}/AOCS/RWModel.cpp (100%) rename src/{Component => components}/AOCS/RWModel.h (100%) rename src/{Component => components}/AOCS/STT.cpp (100%) rename src/{Component => components}/AOCS/STT.h (100%) rename src/{Component => components}/AOCS/SunSensor.cpp (100%) rename src/{Component => components}/AOCS/SunSensor.h (100%) rename src/{Component => components}/AOCS/rw_ode.cpp (100%) rename src/{Component => components}/AOCS/rw_ode.hpp (100%) rename src/{Component => components}/Abstract/ComponentBase.cpp (100%) rename src/{Component => components}/Abstract/ComponentBase.h (100%) rename src/{Component => components}/Abstract/I2cControllerCommunicationBase.cpp (100%) rename src/{Component => components}/Abstract/I2cControllerCommunicationBase.h (100%) rename src/{Component => components}/Abstract/IGPIOCompo.h (100%) rename src/{Component => components}/Abstract/ITickable.h (100%) rename src/{Component => components}/Abstract/InitializeSensorBase.hpp (100%) rename src/{Component => components}/Abstract/InitializeSensorBase_tfs.hpp (100%) rename src/{Component => components}/Abstract/ObcCommunicationBase.cpp (100%) rename src/{Component => components}/Abstract/ObcCommunicationBase.h (100%) rename src/{Component => components}/Abstract/ObcGpioBase.cpp (100%) rename src/{Component => components}/Abstract/ObcGpioBase.h (100%) rename src/{Component => components}/Abstract/ObcI2cTargetCommunicationBase.cpp (100%) rename src/{Component => components}/Abstract/ObcI2cTargetCommunicationBase.h (100%) rename src/{Component => components}/Abstract/SensorBase.h (100%) rename src/{Component => components}/Abstract/SensorBase_tfs.hpp (100%) rename src/{Component => components}/CDH/OBC.cpp (100%) rename src/{Component => components}/CDH/OBC.h (100%) rename src/{Component => components}/CDH/OBC_C2A.cpp (100%) rename src/{Component => components}/CDH/OBC_C2A.h (100%) rename src/{Component => components}/CMakeLists.txt (100%) rename src/{Component => components}/CommGS/Antenna.cpp (100%) rename src/{Component => components}/CommGS/Antenna.hpp (100%) rename src/{Component => components}/CommGS/AntennaRadiationPattern.cpp (100%) rename src/{Component => components}/CommGS/AntennaRadiationPattern.hpp (100%) rename src/{Component => components}/CommGS/GScalculator.cpp (100%) rename src/{Component => components}/CommGS/GScalculator.h (99%) rename src/{Component => components}/CommGS/InitAntenna.cpp (100%) rename src/{Component => components}/CommGS/InitAntenna.hpp (88%) rename src/{Component => components}/CommGS/InitGsCalculator.cpp (100%) rename src/{Component => components}/CommGS/InitGsCalculator.hpp (87%) rename src/{Component => components}/IdealComponents/ForceGenerator.cpp (100%) rename src/{Component => components}/IdealComponents/ForceGenerator.hpp (98%) rename src/{Component => components}/IdealComponents/InitializeForceGenerator.cpp (100%) rename src/{Component => components}/IdealComponents/InitializeForceGenerator.hpp (100%) rename src/{Component => components}/IdealComponents/InitializeTorqueGenerator.cpp (100%) rename src/{Component => components}/IdealComponents/InitializeTorqueGenerator.hpp (100%) rename src/{Component => components}/IdealComponents/TorqueGenerator.cpp (100%) rename src/{Component => components}/IdealComponents/TorqueGenerator.hpp (98%) rename src/{Component => components}/Mission/Telescope/InitTelescope.cpp (100%) rename src/{Component => components}/Mission/Telescope/InitTelescope.hpp (92%) rename src/{Component => components}/Mission/Telescope/Telescope.cpp (100%) rename src/{Component => components}/Mission/Telescope/Telescope.h (100%) rename src/{Component => components}/Power/BAT.cpp (100%) rename src/{Component => components}/Power/BAT.h (100%) rename src/{Component => components}/Power/CsvScenarioInterface.cpp (100%) rename src/{Component => components}/Power/CsvScenarioInterface.h (100%) rename src/{Component => components}/Power/InitBat.cpp (100%) rename src/{Component => components}/Power/InitBat.hpp (92%) rename src/{Component => components}/Power/InitPcu_InitialStudy.cpp (100%) rename src/{Component => components}/Power/InitPcu_InitialStudy.hpp (93%) rename src/{Component => components}/Power/InitSap.cpp (100%) rename src/{Component => components}/Power/InitSap.hpp (96%) rename src/{Component => components}/Power/PCU.cpp (100%) rename src/{Component => components}/Power/PCU.h (100%) rename src/{Component => components}/Power/PCU_InitialStudy.cpp (98%) rename src/{Component => components}/Power/PCU_InitialStudy.h (100%) rename src/{Component => components}/Power/SAP.cpp (98%) rename src/{Component => components}/Power/SAP.h (100%) rename src/{Component => components}/Propulsion/InitSimpleThruster.cpp (100%) rename src/{Component => components}/Propulsion/InitSimpleThruster.hpp (95%) rename src/{Component => components}/Propulsion/SimpleThruster.cpp (100%) rename src/{Component => components}/Propulsion/SimpleThruster.h (100%) rename src/{Component => components}/Thermal/.gitkeep (100%) rename src/{Component => components}/examples/example_change_structure.cpp (100%) rename src/{Component => components}/examples/example_change_structure.hpp (100%) rename src/{Component => components}/examples/example_i2c_controller_for_hils.cpp (100%) rename src/{Component => components}/examples/example_i2c_controller_for_hils.hpp (100%) rename src/{Component => components}/examples/example_i2c_target_for_hils.cpp (100%) rename src/{Component => components}/examples/example_i2c_target_for_hils.hpp (100%) rename src/{Component => components}/examples/example_serial_communication_for_hils.cpp (100%) rename src/{Component => components}/examples/example_serial_communication_for_hils.hpp (100%) rename src/{Component => components}/examples/example_serial_communication_with_obc.cpp (100%) rename src/{Component => components}/examples/example_serial_communication_with_obc.hpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4621d61ee..2fa2686af 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -68,7 +68,7 @@ add_subdirectory(src/environment/global) add_subdirectory(src/environment/local) add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) -add_subdirectory(src/Component) +add_subdirectory(src/components) add_subdirectory(src/relative_information) add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/log_output) diff --git a/src/Component/AOCS/GNSSReceiver.cpp b/src/components/AOCS/GNSSReceiver.cpp similarity index 100% rename from src/Component/AOCS/GNSSReceiver.cpp rename to src/components/AOCS/GNSSReceiver.cpp diff --git a/src/Component/AOCS/GNSSReceiver.h b/src/components/AOCS/GNSSReceiver.h similarity index 100% rename from src/Component/AOCS/GNSSReceiver.h rename to src/components/AOCS/GNSSReceiver.h diff --git a/src/Component/AOCS/Gyro.cpp b/src/components/AOCS/Gyro.cpp similarity index 100% rename from src/Component/AOCS/Gyro.cpp rename to src/components/AOCS/Gyro.cpp diff --git a/src/Component/AOCS/Gyro.h b/src/components/AOCS/Gyro.h similarity index 100% rename from src/Component/AOCS/Gyro.h rename to src/components/AOCS/Gyro.h diff --git a/src/Component/AOCS/InitGnssReceiver.cpp b/src/components/AOCS/InitGnssReceiver.cpp similarity index 100% rename from src/Component/AOCS/InitGnssReceiver.cpp rename to src/components/AOCS/InitGnssReceiver.cpp diff --git a/src/Component/AOCS/InitGnssReceiver.hpp b/src/components/AOCS/InitGnssReceiver.hpp similarity index 96% rename from src/Component/AOCS/InitGnssReceiver.hpp rename to src/components/AOCS/InitGnssReceiver.hpp index f497f8490..5f3e1d91f 100644 --- a/src/Component/AOCS/InitGnssReceiver.hpp +++ b/src/components/AOCS/InitGnssReceiver.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGNSSReceiver diff --git a/src/Component/AOCS/InitGyro.cpp b/src/components/AOCS/InitGyro.cpp similarity index 100% rename from src/Component/AOCS/InitGyro.cpp rename to src/components/AOCS/InitGyro.cpp diff --git a/src/Component/AOCS/InitGyro.hpp b/src/components/AOCS/InitGyro.hpp similarity index 96% rename from src/Component/AOCS/InitGyro.hpp rename to src/components/AOCS/InitGyro.hpp index cd32949d9..6f7be6ad8 100644 --- a/src/Component/AOCS/InitGyro.hpp +++ b/src/components/AOCS/InitGyro.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGyro diff --git a/src/Component/AOCS/InitMagSensor.cpp b/src/components/AOCS/InitMagSensor.cpp similarity index 100% rename from src/Component/AOCS/InitMagSensor.cpp rename to src/components/AOCS/InitMagSensor.cpp diff --git a/src/Component/AOCS/InitMagSensor.hpp b/src/components/AOCS/InitMagSensor.hpp similarity index 96% rename from src/Component/AOCS/InitMagSensor.hpp rename to src/components/AOCS/InitMagSensor.hpp index 90c981e62..4f3ca4124 100644 --- a/src/Component/AOCS/InitMagSensor.hpp +++ b/src/components/AOCS/InitMagSensor.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitMagSensor diff --git a/src/Component/AOCS/InitMagTorquer.cpp b/src/components/AOCS/InitMagTorquer.cpp similarity index 100% rename from src/Component/AOCS/InitMagTorquer.cpp rename to src/components/AOCS/InitMagTorquer.cpp diff --git a/src/Component/AOCS/InitMagTorquer.hpp b/src/components/AOCS/InitMagTorquer.hpp similarity index 96% rename from src/Component/AOCS/InitMagTorquer.hpp rename to src/components/AOCS/InitMagTorquer.hpp index f1d35557d..1de7356b6 100644 --- a/src/Component/AOCS/InitMagTorquer.hpp +++ b/src/components/AOCS/InitMagTorquer.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitMagTorquer diff --git a/src/Component/AOCS/InitRwModel.cpp b/src/components/AOCS/InitRwModel.cpp similarity index 100% rename from src/Component/AOCS/InitRwModel.cpp rename to src/components/AOCS/InitRwModel.cpp diff --git a/src/Component/AOCS/InitRwModel.hpp b/src/components/AOCS/InitRwModel.hpp similarity index 96% rename from src/Component/AOCS/InitRwModel.hpp rename to src/components/AOCS/InitRwModel.hpp index 2a4efd174..dc93bc2d5 100644 --- a/src/Component/AOCS/InitRwModel.hpp +++ b/src/components/AOCS/InitRwModel.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitRWModel diff --git a/src/Component/AOCS/InitStt.cpp b/src/components/AOCS/InitStt.cpp similarity index 100% rename from src/Component/AOCS/InitStt.cpp rename to src/components/AOCS/InitStt.cpp diff --git a/src/Component/AOCS/InitStt.hpp b/src/components/AOCS/InitStt.hpp similarity index 97% rename from src/Component/AOCS/InitStt.hpp rename to src/components/AOCS/InitStt.hpp index 6759d7a88..2cd47a6c7 100644 --- a/src/Component/AOCS/InitStt.hpp +++ b/src/components/AOCS/InitStt.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitSTT diff --git a/src/Component/AOCS/InitSunSensor.cpp b/src/components/AOCS/InitSunSensor.cpp similarity index 100% rename from src/Component/AOCS/InitSunSensor.cpp rename to src/components/AOCS/InitSunSensor.cpp diff --git a/src/Component/AOCS/InitSunSensor.hpp b/src/components/AOCS/InitSunSensor.hpp similarity index 96% rename from src/Component/AOCS/InitSunSensor.hpp rename to src/components/AOCS/InitSunSensor.hpp index 4532cba3d..ee19e139a 100644 --- a/src/Component/AOCS/InitSunSensor.hpp +++ b/src/components/AOCS/InitSunSensor.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitSunSensor diff --git a/src/Component/AOCS/MagSensor.cpp b/src/components/AOCS/MagSensor.cpp similarity index 100% rename from src/Component/AOCS/MagSensor.cpp rename to src/components/AOCS/MagSensor.cpp diff --git a/src/Component/AOCS/MagSensor.h b/src/components/AOCS/MagSensor.h similarity index 100% rename from src/Component/AOCS/MagSensor.h rename to src/components/AOCS/MagSensor.h diff --git a/src/Component/AOCS/MagTorquer.cpp b/src/components/AOCS/MagTorquer.cpp similarity index 100% rename from src/Component/AOCS/MagTorquer.cpp rename to src/components/AOCS/MagTorquer.cpp diff --git a/src/Component/AOCS/MagTorquer.h b/src/components/AOCS/MagTorquer.h similarity index 100% rename from src/Component/AOCS/MagTorquer.h rename to src/components/AOCS/MagTorquer.h diff --git a/src/Component/AOCS/RWJitter.cpp b/src/components/AOCS/RWJitter.cpp similarity index 100% rename from src/Component/AOCS/RWJitter.cpp rename to src/components/AOCS/RWJitter.cpp diff --git a/src/Component/AOCS/RWJitter.h b/src/components/AOCS/RWJitter.h similarity index 100% rename from src/Component/AOCS/RWJitter.h rename to src/components/AOCS/RWJitter.h diff --git a/src/Component/AOCS/RWModel.cpp b/src/components/AOCS/RWModel.cpp similarity index 100% rename from src/Component/AOCS/RWModel.cpp rename to src/components/AOCS/RWModel.cpp diff --git a/src/Component/AOCS/RWModel.h b/src/components/AOCS/RWModel.h similarity index 100% rename from src/Component/AOCS/RWModel.h rename to src/components/AOCS/RWModel.h diff --git a/src/Component/AOCS/STT.cpp b/src/components/AOCS/STT.cpp similarity index 100% rename from src/Component/AOCS/STT.cpp rename to src/components/AOCS/STT.cpp diff --git a/src/Component/AOCS/STT.h b/src/components/AOCS/STT.h similarity index 100% rename from src/Component/AOCS/STT.h rename to src/components/AOCS/STT.h diff --git a/src/Component/AOCS/SunSensor.cpp b/src/components/AOCS/SunSensor.cpp similarity index 100% rename from src/Component/AOCS/SunSensor.cpp rename to src/components/AOCS/SunSensor.cpp diff --git a/src/Component/AOCS/SunSensor.h b/src/components/AOCS/SunSensor.h similarity index 100% rename from src/Component/AOCS/SunSensor.h rename to src/components/AOCS/SunSensor.h diff --git a/src/Component/AOCS/rw_ode.cpp b/src/components/AOCS/rw_ode.cpp similarity index 100% rename from src/Component/AOCS/rw_ode.cpp rename to src/components/AOCS/rw_ode.cpp diff --git a/src/Component/AOCS/rw_ode.hpp b/src/components/AOCS/rw_ode.hpp similarity index 100% rename from src/Component/AOCS/rw_ode.hpp rename to src/components/AOCS/rw_ode.hpp diff --git a/src/Component/Abstract/ComponentBase.cpp b/src/components/Abstract/ComponentBase.cpp similarity index 100% rename from src/Component/Abstract/ComponentBase.cpp rename to src/components/Abstract/ComponentBase.cpp diff --git a/src/Component/Abstract/ComponentBase.h b/src/components/Abstract/ComponentBase.h similarity index 100% rename from src/Component/Abstract/ComponentBase.h rename to src/components/Abstract/ComponentBase.h diff --git a/src/Component/Abstract/I2cControllerCommunicationBase.cpp b/src/components/Abstract/I2cControllerCommunicationBase.cpp similarity index 100% rename from src/Component/Abstract/I2cControllerCommunicationBase.cpp rename to src/components/Abstract/I2cControllerCommunicationBase.cpp diff --git a/src/Component/Abstract/I2cControllerCommunicationBase.h b/src/components/Abstract/I2cControllerCommunicationBase.h similarity index 100% rename from src/Component/Abstract/I2cControllerCommunicationBase.h rename to src/components/Abstract/I2cControllerCommunicationBase.h diff --git a/src/Component/Abstract/IGPIOCompo.h b/src/components/Abstract/IGPIOCompo.h similarity index 100% rename from src/Component/Abstract/IGPIOCompo.h rename to src/components/Abstract/IGPIOCompo.h diff --git a/src/Component/Abstract/ITickable.h b/src/components/Abstract/ITickable.h similarity index 100% rename from src/Component/Abstract/ITickable.h rename to src/components/Abstract/ITickable.h diff --git a/src/Component/Abstract/InitializeSensorBase.hpp b/src/components/Abstract/InitializeSensorBase.hpp similarity index 100% rename from src/Component/Abstract/InitializeSensorBase.hpp rename to src/components/Abstract/InitializeSensorBase.hpp diff --git a/src/Component/Abstract/InitializeSensorBase_tfs.hpp b/src/components/Abstract/InitializeSensorBase_tfs.hpp similarity index 100% rename from src/Component/Abstract/InitializeSensorBase_tfs.hpp rename to src/components/Abstract/InitializeSensorBase_tfs.hpp diff --git a/src/Component/Abstract/ObcCommunicationBase.cpp b/src/components/Abstract/ObcCommunicationBase.cpp similarity index 100% rename from src/Component/Abstract/ObcCommunicationBase.cpp rename to src/components/Abstract/ObcCommunicationBase.cpp diff --git a/src/Component/Abstract/ObcCommunicationBase.h b/src/components/Abstract/ObcCommunicationBase.h similarity index 100% rename from src/Component/Abstract/ObcCommunicationBase.h rename to src/components/Abstract/ObcCommunicationBase.h diff --git a/src/Component/Abstract/ObcGpioBase.cpp b/src/components/Abstract/ObcGpioBase.cpp similarity index 100% rename from src/Component/Abstract/ObcGpioBase.cpp rename to src/components/Abstract/ObcGpioBase.cpp diff --git a/src/Component/Abstract/ObcGpioBase.h b/src/components/Abstract/ObcGpioBase.h similarity index 100% rename from src/Component/Abstract/ObcGpioBase.h rename to src/components/Abstract/ObcGpioBase.h diff --git a/src/Component/Abstract/ObcI2cTargetCommunicationBase.cpp b/src/components/Abstract/ObcI2cTargetCommunicationBase.cpp similarity index 100% rename from src/Component/Abstract/ObcI2cTargetCommunicationBase.cpp rename to src/components/Abstract/ObcI2cTargetCommunicationBase.cpp diff --git a/src/Component/Abstract/ObcI2cTargetCommunicationBase.h b/src/components/Abstract/ObcI2cTargetCommunicationBase.h similarity index 100% rename from src/Component/Abstract/ObcI2cTargetCommunicationBase.h rename to src/components/Abstract/ObcI2cTargetCommunicationBase.h diff --git a/src/Component/Abstract/SensorBase.h b/src/components/Abstract/SensorBase.h similarity index 100% rename from src/Component/Abstract/SensorBase.h rename to src/components/Abstract/SensorBase.h diff --git a/src/Component/Abstract/SensorBase_tfs.hpp b/src/components/Abstract/SensorBase_tfs.hpp similarity index 100% rename from src/Component/Abstract/SensorBase_tfs.hpp rename to src/components/Abstract/SensorBase_tfs.hpp diff --git a/src/Component/CDH/OBC.cpp b/src/components/CDH/OBC.cpp similarity index 100% rename from src/Component/CDH/OBC.cpp rename to src/components/CDH/OBC.cpp diff --git a/src/Component/CDH/OBC.h b/src/components/CDH/OBC.h similarity index 100% rename from src/Component/CDH/OBC.h rename to src/components/CDH/OBC.h diff --git a/src/Component/CDH/OBC_C2A.cpp b/src/components/CDH/OBC_C2A.cpp similarity index 100% rename from src/Component/CDH/OBC_C2A.cpp rename to src/components/CDH/OBC_C2A.cpp diff --git a/src/Component/CDH/OBC_C2A.h b/src/components/CDH/OBC_C2A.h similarity index 100% rename from src/Component/CDH/OBC_C2A.h rename to src/components/CDH/OBC_C2A.h diff --git a/src/Component/CMakeLists.txt b/src/components/CMakeLists.txt similarity index 100% rename from src/Component/CMakeLists.txt rename to src/components/CMakeLists.txt diff --git a/src/Component/CommGS/Antenna.cpp b/src/components/CommGS/Antenna.cpp similarity index 100% rename from src/Component/CommGS/Antenna.cpp rename to src/components/CommGS/Antenna.cpp diff --git a/src/Component/CommGS/Antenna.hpp b/src/components/CommGS/Antenna.hpp similarity index 100% rename from src/Component/CommGS/Antenna.hpp rename to src/components/CommGS/Antenna.hpp diff --git a/src/Component/CommGS/AntennaRadiationPattern.cpp b/src/components/CommGS/AntennaRadiationPattern.cpp similarity index 100% rename from src/Component/CommGS/AntennaRadiationPattern.cpp rename to src/components/CommGS/AntennaRadiationPattern.cpp diff --git a/src/Component/CommGS/AntennaRadiationPattern.hpp b/src/components/CommGS/AntennaRadiationPattern.hpp similarity index 100% rename from src/Component/CommGS/AntennaRadiationPattern.hpp rename to src/components/CommGS/AntennaRadiationPattern.hpp diff --git a/src/Component/CommGS/GScalculator.cpp b/src/components/CommGS/GScalculator.cpp similarity index 100% rename from src/Component/CommGS/GScalculator.cpp rename to src/components/CommGS/GScalculator.cpp diff --git a/src/Component/CommGS/GScalculator.h b/src/components/CommGS/GScalculator.h similarity index 99% rename from src/Component/CommGS/GScalculator.h rename to src/components/CommGS/GScalculator.h index 12725a6df..f59cd0d6d 100644 --- a/src/Component/CommGS/GScalculator.h +++ b/src/components/CommGS/GScalculator.h @@ -8,7 +8,7 @@ #include -#include +#include #include #include #include diff --git a/src/Component/CommGS/InitAntenna.cpp b/src/components/CommGS/InitAntenna.cpp similarity index 100% rename from src/Component/CommGS/InitAntenna.cpp rename to src/components/CommGS/InitAntenna.cpp diff --git a/src/Component/CommGS/InitAntenna.hpp b/src/components/CommGS/InitAntenna.hpp similarity index 88% rename from src/Component/CommGS/InitAntenna.hpp rename to src/components/CommGS/InitAntenna.hpp index f08e79709..2542de7d5 100644 --- a/src/Component/CommGS/InitAntenna.hpp +++ b/src/components/CommGS/InitAntenna.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitAntenna diff --git a/src/Component/CommGS/InitGsCalculator.cpp b/src/components/CommGS/InitGsCalculator.cpp similarity index 100% rename from src/Component/CommGS/InitGsCalculator.cpp rename to src/components/CommGS/InitGsCalculator.cpp diff --git a/src/Component/CommGS/InitGsCalculator.hpp b/src/components/CommGS/InitGsCalculator.hpp similarity index 87% rename from src/Component/CommGS/InitGsCalculator.hpp rename to src/components/CommGS/InitGsCalculator.hpp index e80e8cc58..a086434dc 100644 --- a/src/Component/CommGS/InitGsCalculator.hpp +++ b/src/components/CommGS/InitGsCalculator.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /* * @fn InitGscalculator diff --git a/src/Component/IdealComponents/ForceGenerator.cpp b/src/components/IdealComponents/ForceGenerator.cpp similarity index 100% rename from src/Component/IdealComponents/ForceGenerator.cpp rename to src/components/IdealComponents/ForceGenerator.cpp diff --git a/src/Component/IdealComponents/ForceGenerator.hpp b/src/components/IdealComponents/ForceGenerator.hpp similarity index 98% rename from src/Component/IdealComponents/ForceGenerator.hpp rename to src/components/IdealComponents/ForceGenerator.hpp index 6728ff788..1d744b6e5 100644 --- a/src/Component/IdealComponents/ForceGenerator.hpp +++ b/src/components/IdealComponents/ForceGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/IdealComponents/InitializeForceGenerator.cpp b/src/components/IdealComponents/InitializeForceGenerator.cpp similarity index 100% rename from src/Component/IdealComponents/InitializeForceGenerator.cpp rename to src/components/IdealComponents/InitializeForceGenerator.cpp diff --git a/src/Component/IdealComponents/InitializeForceGenerator.hpp b/src/components/IdealComponents/InitializeForceGenerator.hpp similarity index 100% rename from src/Component/IdealComponents/InitializeForceGenerator.hpp rename to src/components/IdealComponents/InitializeForceGenerator.hpp diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.cpp b/src/components/IdealComponents/InitializeTorqueGenerator.cpp similarity index 100% rename from src/Component/IdealComponents/InitializeTorqueGenerator.cpp rename to src/components/IdealComponents/InitializeTorqueGenerator.cpp diff --git a/src/Component/IdealComponents/InitializeTorqueGenerator.hpp b/src/components/IdealComponents/InitializeTorqueGenerator.hpp similarity index 100% rename from src/Component/IdealComponents/InitializeTorqueGenerator.hpp rename to src/components/IdealComponents/InitializeTorqueGenerator.hpp diff --git a/src/Component/IdealComponents/TorqueGenerator.cpp b/src/components/IdealComponents/TorqueGenerator.cpp similarity index 100% rename from src/Component/IdealComponents/TorqueGenerator.cpp rename to src/components/IdealComponents/TorqueGenerator.cpp diff --git a/src/Component/IdealComponents/TorqueGenerator.hpp b/src/components/IdealComponents/TorqueGenerator.hpp similarity index 98% rename from src/Component/IdealComponents/TorqueGenerator.hpp rename to src/components/IdealComponents/TorqueGenerator.hpp index 1c600b0a2..a690032a4 100644 --- a/src/Component/IdealComponents/TorqueGenerator.hpp +++ b/src/components/IdealComponents/TorqueGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/Component/Mission/Telescope/InitTelescope.cpp b/src/components/Mission/Telescope/InitTelescope.cpp similarity index 100% rename from src/Component/Mission/Telescope/InitTelescope.cpp rename to src/components/Mission/Telescope/InitTelescope.cpp diff --git a/src/Component/Mission/Telescope/InitTelescope.hpp b/src/components/Mission/Telescope/InitTelescope.hpp similarity index 92% rename from src/Component/Mission/Telescope/InitTelescope.hpp rename to src/components/Mission/Telescope/InitTelescope.hpp index 935ba2bf0..9daed1c85 100644 --- a/src/Component/Mission/Telescope/InitTelescope.hpp +++ b/src/components/Mission/Telescope/InitTelescope.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitTelescope diff --git a/src/Component/Mission/Telescope/Telescope.cpp b/src/components/Mission/Telescope/Telescope.cpp similarity index 100% rename from src/Component/Mission/Telescope/Telescope.cpp rename to src/components/Mission/Telescope/Telescope.cpp diff --git a/src/Component/Mission/Telescope/Telescope.h b/src/components/Mission/Telescope/Telescope.h similarity index 100% rename from src/Component/Mission/Telescope/Telescope.h rename to src/components/Mission/Telescope/Telescope.h diff --git a/src/Component/Power/BAT.cpp b/src/components/Power/BAT.cpp similarity index 100% rename from src/Component/Power/BAT.cpp rename to src/components/Power/BAT.cpp diff --git a/src/Component/Power/BAT.h b/src/components/Power/BAT.h similarity index 100% rename from src/Component/Power/BAT.h rename to src/components/Power/BAT.h diff --git a/src/Component/Power/CsvScenarioInterface.cpp b/src/components/Power/CsvScenarioInterface.cpp similarity index 100% rename from src/Component/Power/CsvScenarioInterface.cpp rename to src/components/Power/CsvScenarioInterface.cpp diff --git a/src/Component/Power/CsvScenarioInterface.h b/src/components/Power/CsvScenarioInterface.h similarity index 100% rename from src/Component/Power/CsvScenarioInterface.h rename to src/components/Power/CsvScenarioInterface.h diff --git a/src/Component/Power/InitBat.cpp b/src/components/Power/InitBat.cpp similarity index 100% rename from src/Component/Power/InitBat.cpp rename to src/components/Power/InitBat.cpp diff --git a/src/Component/Power/InitBat.hpp b/src/components/Power/InitBat.hpp similarity index 92% rename from src/Component/Power/InitBat.hpp rename to src/components/Power/InitBat.hpp index dc124e48a..2ab188883 100644 --- a/src/Component/Power/InitBat.hpp +++ b/src/components/Power/InitBat.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitBAT diff --git a/src/Component/Power/InitPcu_InitialStudy.cpp b/src/components/Power/InitPcu_InitialStudy.cpp similarity index 100% rename from src/Component/Power/InitPcu_InitialStudy.cpp rename to src/components/Power/InitPcu_InitialStudy.cpp diff --git a/src/Component/Power/InitPcu_InitialStudy.hpp b/src/components/Power/InitPcu_InitialStudy.hpp similarity index 93% rename from src/Component/Power/InitPcu_InitialStudy.hpp rename to src/components/Power/InitPcu_InitialStudy.hpp index 872fccafa..1974e18fa 100644 --- a/src/Component/Power/InitPcu_InitialStudy.hpp +++ b/src/components/Power/InitPcu_InitialStudy.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitPCU_InitialStudy diff --git a/src/Component/Power/InitSap.cpp b/src/components/Power/InitSap.cpp similarity index 100% rename from src/Component/Power/InitSap.cpp rename to src/components/Power/InitSap.cpp diff --git a/src/Component/Power/InitSap.hpp b/src/components/Power/InitSap.hpp similarity index 96% rename from src/Component/Power/InitSap.hpp rename to src/components/Power/InitSap.hpp index 7262f1069..ff40f4ae1 100644 --- a/src/Component/Power/InitSap.hpp +++ b/src/components/Power/InitSap.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitSAP diff --git a/src/Component/Power/PCU.cpp b/src/components/Power/PCU.cpp similarity index 100% rename from src/Component/Power/PCU.cpp rename to src/components/Power/PCU.cpp diff --git a/src/Component/Power/PCU.h b/src/components/Power/PCU.h similarity index 100% rename from src/Component/Power/PCU.h rename to src/components/Power/PCU.h diff --git a/src/Component/Power/PCU_InitialStudy.cpp b/src/components/Power/PCU_InitialStudy.cpp similarity index 98% rename from src/Component/Power/PCU_InitialStudy.cpp rename to src/components/Power/PCU_InitialStudy.cpp index bca9c9529..ddb68f9be 100644 --- a/src/Component/Power/PCU_InitialStudy.cpp +++ b/src/components/Power/PCU_InitialStudy.cpp @@ -5,7 +5,7 @@ #include "PCU_InitialStudy.h" -#include +#include #include #include diff --git a/src/Component/Power/PCU_InitialStudy.h b/src/components/Power/PCU_InitialStudy.h similarity index 100% rename from src/Component/Power/PCU_InitialStudy.h rename to src/components/Power/PCU_InitialStudy.h diff --git a/src/Component/Power/SAP.cpp b/src/components/Power/SAP.cpp similarity index 98% rename from src/Component/Power/SAP.cpp rename to src/components/Power/SAP.cpp index 313ee8661..714f89866 100644 --- a/src/Component/Power/SAP.cpp +++ b/src/components/Power/SAP.cpp @@ -1,6 +1,6 @@ #include "SAP.h" -#include +#include #include diff --git a/src/Component/Power/SAP.h b/src/components/Power/SAP.h similarity index 100% rename from src/Component/Power/SAP.h rename to src/components/Power/SAP.h diff --git a/src/Component/Propulsion/InitSimpleThruster.cpp b/src/components/Propulsion/InitSimpleThruster.cpp similarity index 100% rename from src/Component/Propulsion/InitSimpleThruster.cpp rename to src/components/Propulsion/InitSimpleThruster.cpp diff --git a/src/Component/Propulsion/InitSimpleThruster.hpp b/src/components/Propulsion/InitSimpleThruster.hpp similarity index 95% rename from src/Component/Propulsion/InitSimpleThruster.hpp rename to src/components/Propulsion/InitSimpleThruster.hpp index fb3b6e7b2..55bf3154e 100644 --- a/src/Component/Propulsion/InitSimpleThruster.hpp +++ b/src/components/Propulsion/InitSimpleThruster.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitSimpleThruster diff --git a/src/Component/Propulsion/SimpleThruster.cpp b/src/components/Propulsion/SimpleThruster.cpp similarity index 100% rename from src/Component/Propulsion/SimpleThruster.cpp rename to src/components/Propulsion/SimpleThruster.cpp diff --git a/src/Component/Propulsion/SimpleThruster.h b/src/components/Propulsion/SimpleThruster.h similarity index 100% rename from src/Component/Propulsion/SimpleThruster.h rename to src/components/Propulsion/SimpleThruster.h diff --git a/src/Component/Thermal/.gitkeep b/src/components/Thermal/.gitkeep similarity index 100% rename from src/Component/Thermal/.gitkeep rename to src/components/Thermal/.gitkeep diff --git a/src/Component/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp similarity index 100% rename from src/Component/examples/example_change_structure.cpp rename to src/components/examples/example_change_structure.cpp diff --git a/src/Component/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp similarity index 100% rename from src/Component/examples/example_change_structure.hpp rename to src/components/examples/example_change_structure.hpp diff --git a/src/Component/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp similarity index 100% rename from src/Component/examples/example_i2c_controller_for_hils.cpp rename to src/components/examples/example_i2c_controller_for_hils.cpp diff --git a/src/Component/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp similarity index 100% rename from src/Component/examples/example_i2c_controller_for_hils.hpp rename to src/components/examples/example_i2c_controller_for_hils.hpp diff --git a/src/Component/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp similarity index 100% rename from src/Component/examples/example_i2c_target_for_hils.cpp rename to src/components/examples/example_i2c_target_for_hils.cpp diff --git a/src/Component/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp similarity index 100% rename from src/Component/examples/example_i2c_target_for_hils.hpp rename to src/components/examples/example_i2c_target_for_hils.hpp diff --git a/src/Component/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp similarity index 100% rename from src/Component/examples/example_serial_communication_for_hils.cpp rename to src/components/examples/example_serial_communication_for_hils.cpp diff --git a/src/Component/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp similarity index 100% rename from src/Component/examples/example_serial_communication_for_hils.hpp rename to src/components/examples/example_serial_communication_for_hils.hpp diff --git a/src/Component/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp similarity index 100% rename from src/Component/examples/example_serial_communication_with_obc.cpp rename to src/components/examples/example_serial_communication_with_obc.cpp diff --git a/src/Component/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp similarity index 100% rename from src/Component/examples/example_serial_communication_with_obc.hpp rename to src/components/examples/example_serial_communication_with_obc.hpp diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 6254eec60..621ee29a6 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ #define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ -#include +#include #include diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index afeaf5401..672ad8fd6 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -8,7 +8,7 @@ #ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ #define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ -#include +#include #include #include diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/interface/sils/ports/gpio_port.hpp index 6b09e8584..99efa06da 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/interface/sils/ports/gpio_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ #define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ -#include +#include #define GPIO_HIGH true #define GPIO_LOW false diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 0db4f1006..c4108b7b6 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ -#include +#include -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index b89314fdc..1865fc6f6 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ -#include -#include +#include +#include /** * @class SampleGSComponents diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 34e9963da..0026bf210 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,26 +6,26 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include -#include +#include +#include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include From 9a18a2578abc0de2aefcced574da31c852a76695 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:50:41 +0100 Subject: [PATCH 0278/1086] Rename Abstract --- src/components/AOCS/GNSSReceiver.h | 5 ++--- src/components/AOCS/Gyro.h | 7 +++---- src/components/AOCS/InitGyro.cpp | 2 +- src/components/AOCS/InitMagSensor.cpp | 2 +- src/components/AOCS/MagSensor.h | 4 ++-- src/components/AOCS/MagTorquer.h | 2 +- src/components/AOCS/RWModel.h | 2 +- src/components/AOCS/STT.h | 2 +- src/components/AOCS/SunSensor.h | 2 +- src/components/CDH/OBC.h | 2 +- src/components/CMakeLists.txt | 10 +++++----- src/components/IdealComponents/ForceGenerator.hpp | 2 +- src/components/IdealComponents/TorqueGenerator.hpp | 2 +- src/components/Mission/Telescope/Telescope.h | 2 +- src/components/Power/BAT.h | 2 +- src/components/Power/PCU.h | 2 +- src/components/Power/PCU_InitialStudy.h | 2 +- src/components/Power/SAP.h | 2 +- src/components/Propulsion/SimpleThruster.h | 2 +- .../{Abstract => base_classes}/ComponentBase.cpp | 0 .../{Abstract => base_classes}/ComponentBase.h | 0 .../I2cControllerCommunicationBase.cpp | 0 .../I2cControllerCommunicationBase.h | 0 src/components/{Abstract => base_classes}/IGPIOCompo.h | 0 src/components/{Abstract => base_classes}/ITickable.h | 0 .../InitializeSensorBase.hpp | 0 .../InitializeSensorBase_tfs.hpp | 0 .../ObcCommunicationBase.cpp | 0 .../{Abstract => base_classes}/ObcCommunicationBase.h | 0 .../{Abstract => base_classes}/ObcGpioBase.cpp | 0 .../{Abstract => base_classes}/ObcGpioBase.h | 0 .../ObcI2cTargetCommunicationBase.cpp | 0 .../ObcI2cTargetCommunicationBase.h | 0 src/components/{Abstract => base_classes}/SensorBase.h | 0 .../{Abstract => base_classes}/SensorBase_tfs.hpp | 0 src/components/examples/example_change_structure.hpp | 2 +- .../examples/example_i2c_controller_for_hils.hpp | 4 ++-- .../examples/example_i2c_target_for_hils.hpp | 4 ++-- .../examples/example_serial_communication_for_hils.hpp | 4 ++-- .../examples/example_serial_communication_with_obc.hpp | 6 +++--- src/environment/global/clock_generator.hpp | 2 +- src/interface/hils/com_port_interface.hpp | 2 +- src/interface/sils/ports/gpio_port.hpp | 2 +- 43 files changed, 40 insertions(+), 42 deletions(-) rename src/components/{Abstract => base_classes}/ComponentBase.cpp (100%) rename src/components/{Abstract => base_classes}/ComponentBase.h (100%) rename src/components/{Abstract => base_classes}/I2cControllerCommunicationBase.cpp (100%) rename src/components/{Abstract => base_classes}/I2cControllerCommunicationBase.h (100%) rename src/components/{Abstract => base_classes}/IGPIOCompo.h (100%) rename src/components/{Abstract => base_classes}/ITickable.h (100%) rename src/components/{Abstract => base_classes}/InitializeSensorBase.hpp (100%) rename src/components/{Abstract => base_classes}/InitializeSensorBase_tfs.hpp (100%) rename src/components/{Abstract => base_classes}/ObcCommunicationBase.cpp (100%) rename src/components/{Abstract => base_classes}/ObcCommunicationBase.h (100%) rename src/components/{Abstract => base_classes}/ObcGpioBase.cpp (100%) rename src/components/{Abstract => base_classes}/ObcGpioBase.h (100%) rename src/components/{Abstract => base_classes}/ObcI2cTargetCommunicationBase.cpp (100%) rename src/components/{Abstract => base_classes}/ObcI2cTargetCommunicationBase.h (100%) rename src/components/{Abstract => base_classes}/SensorBase.h (100%) rename src/components/{Abstract => base_classes}/SensorBase_tfs.hpp (100%) diff --git a/src/components/AOCS/GNSSReceiver.h b/src/components/AOCS/GNSSReceiver.h index 0d28c1641..3a5120ef8 100644 --- a/src/components/AOCS/GNSSReceiver.h +++ b/src/components/AOCS/GNSSReceiver.h @@ -5,15 +5,14 @@ #pragma once -#include - #include #include #include #include #include +#include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" using libra::Vector; diff --git a/src/components/AOCS/Gyro.h b/src/components/AOCS/Gyro.h index 245d6a434..3cd881c1a 100644 --- a/src/components/AOCS/Gyro.h +++ b/src/components/AOCS/Gyro.h @@ -6,13 +6,12 @@ #ifndef Gyro_H_ #define Gyro_H_ -#include - #include #include +#include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/SensorBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/SensorBase.h" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/AOCS/InitGyro.cpp b/src/components/AOCS/InitGyro.cpp index 9b6a295db..e52504c68 100644 --- a/src/components/AOCS/InitGyro.cpp +++ b/src/components/AOCS/InitGyro.cpp @@ -6,7 +6,7 @@ #include -#include "../Abstract/InitializeSensorBase.hpp" +#include "../base_classes/InitializeSensorBase.hpp" Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); diff --git a/src/components/AOCS/InitMagSensor.cpp b/src/components/AOCS/InitMagSensor.cpp index f419675ab..c65346c68 100644 --- a/src/components/AOCS/InitMagSensor.cpp +++ b/src/components/AOCS/InitMagSensor.cpp @@ -4,7 +4,7 @@ */ #include "InitMagSensor.hpp" -#include "../Abstract/InitializeSensorBase.hpp" +#include "../base_classes/InitializeSensorBase.hpp" #include "interface/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { diff --git a/src/components/AOCS/MagSensor.h b/src/components/AOCS/MagSensor.h index ac0d0443a..c4553da63 100644 --- a/src/components/AOCS/MagSensor.h +++ b/src/components/AOCS/MagSensor.h @@ -11,8 +11,8 @@ #include #include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/SensorBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/SensorBase.h" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/AOCS/MagTorquer.h b/src/components/AOCS/MagTorquer.h index 42b4ebfcb..8f5c19cf7 100644 --- a/src/components/AOCS/MagTorquer.h +++ b/src/components/AOCS/MagTorquer.h @@ -15,7 +15,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" const size_t kMtqDim = 3; //!< Dimension of magnetorquer diff --git a/src/components/AOCS/RWModel.h b/src/components/AOCS/RWModel.h index 7a01033ae..5c7bfa3bf 100644 --- a/src/components/AOCS/RWModel.h +++ b/src/components/AOCS/RWModel.h @@ -13,7 +13,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" #include "RWJitter.h" #include "rw_ode.hpp" diff --git a/src/components/AOCS/STT.h b/src/components/AOCS/STT.h index d2fae33ed..cefb3f10c 100644 --- a/src/components/AOCS/STT.h +++ b/src/components/AOCS/STT.h @@ -18,7 +18,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" #include "dynamics/dynamics.hpp" /* diff --git a/src/components/AOCS/SunSensor.h b/src/components/AOCS/SunSensor.h index 7a1125498..015afdeda 100644 --- a/src/components/AOCS/SunSensor.h +++ b/src/components/AOCS/SunSensor.h @@ -14,7 +14,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /* * @class SunSensor diff --git a/src/components/CDH/OBC.h b/src/components/CDH/OBC.h index 55a58d5f6..4279c111f 100644 --- a/src/components/CDH/OBC.h +++ b/src/components/CDH/OBC.h @@ -9,7 +9,7 @@ #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /* * @class OBC diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 2dcf8cd1e..cfc19a38a 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -2,11 +2,11 @@ project(COMPONENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Abstract/ComponentBase.cpp - Abstract/ObcCommunicationBase.cpp - Abstract/I2cControllerCommunicationBase.cpp - Abstract/ObcI2cTargetCommunicationBase.cpp - Abstract/ObcGpioBase.cpp + base_classes/ComponentBase.cpp + base_classes/ObcCommunicationBase.cpp + base_classes/I2cControllerCommunicationBase.cpp + base_classes/ObcI2cTargetCommunicationBase.cpp + base_classes/ObcGpioBase.cpp AOCS/Gyro.cpp AOCS/InitGyro.cpp diff --git a/src/components/IdealComponents/ForceGenerator.hpp b/src/components/IdealComponents/ForceGenerator.hpp index 1d744b6e5..eb6bfde5b 100644 --- a/src/components/IdealComponents/ForceGenerator.hpp +++ b/src/components/IdealComponents/ForceGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/IdealComponents/TorqueGenerator.hpp b/src/components/IdealComponents/TorqueGenerator.hpp index a690032a4..2ad78ced3 100644 --- a/src/components/IdealComponents/TorqueGenerator.hpp +++ b/src/components/IdealComponents/TorqueGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/Mission/Telescope/Telescope.h b/src/components/Mission/Telescope/Telescope.h index 6f9892ef9..83640524e 100644 --- a/src/components/Mission/Telescope/Telescope.h +++ b/src/components/Mission/Telescope/Telescope.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/Power/BAT.h b/src/components/Power/BAT.h index 7ba8fa777..cc1beac04 100644 --- a/src/components/Power/BAT.h +++ b/src/components/Power/BAT.h @@ -8,7 +8,7 @@ #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /* * @class BAT diff --git a/src/components/Power/PCU.h b/src/components/Power/PCU.h index d0ee1042d..6437788fe 100644 --- a/src/components/Power/PCU.h +++ b/src/components/Power/PCU.h @@ -9,7 +9,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /* * @class PCU diff --git a/src/components/Power/PCU_InitialStudy.h b/src/components/Power/PCU_InitialStudy.h index 0c6899abb..078d5554e 100644 --- a/src/components/Power/PCU_InitialStudy.h +++ b/src/components/Power/PCU_InitialStudy.h @@ -8,7 +8,7 @@ #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" #include "BAT.h" #include "SAP.h" diff --git a/src/components/Power/SAP.h b/src/components/Power/SAP.h index da456799e..b82f67490 100644 --- a/src/components/Power/SAP.h +++ b/src/components/Power/SAP.h @@ -10,7 +10,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" class SAP : public ComponentBase, public ILoggable { public: diff --git a/src/components/Propulsion/SimpleThruster.h b/src/components/Propulsion/SimpleThruster.h index f88d75e4a..a74e2b8eb 100644 --- a/src/components/Propulsion/SimpleThruster.h +++ b/src/components/Propulsion/SimpleThruster.h @@ -12,7 +12,7 @@ #include #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /* * @class SimpleThruster diff --git a/src/components/Abstract/ComponentBase.cpp b/src/components/base_classes/ComponentBase.cpp similarity index 100% rename from src/components/Abstract/ComponentBase.cpp rename to src/components/base_classes/ComponentBase.cpp diff --git a/src/components/Abstract/ComponentBase.h b/src/components/base_classes/ComponentBase.h similarity index 100% rename from src/components/Abstract/ComponentBase.h rename to src/components/base_classes/ComponentBase.h diff --git a/src/components/Abstract/I2cControllerCommunicationBase.cpp b/src/components/base_classes/I2cControllerCommunicationBase.cpp similarity index 100% rename from src/components/Abstract/I2cControllerCommunicationBase.cpp rename to src/components/base_classes/I2cControllerCommunicationBase.cpp diff --git a/src/components/Abstract/I2cControllerCommunicationBase.h b/src/components/base_classes/I2cControllerCommunicationBase.h similarity index 100% rename from src/components/Abstract/I2cControllerCommunicationBase.h rename to src/components/base_classes/I2cControllerCommunicationBase.h diff --git a/src/components/Abstract/IGPIOCompo.h b/src/components/base_classes/IGPIOCompo.h similarity index 100% rename from src/components/Abstract/IGPIOCompo.h rename to src/components/base_classes/IGPIOCompo.h diff --git a/src/components/Abstract/ITickable.h b/src/components/base_classes/ITickable.h similarity index 100% rename from src/components/Abstract/ITickable.h rename to src/components/base_classes/ITickable.h diff --git a/src/components/Abstract/InitializeSensorBase.hpp b/src/components/base_classes/InitializeSensorBase.hpp similarity index 100% rename from src/components/Abstract/InitializeSensorBase.hpp rename to src/components/base_classes/InitializeSensorBase.hpp diff --git a/src/components/Abstract/InitializeSensorBase_tfs.hpp b/src/components/base_classes/InitializeSensorBase_tfs.hpp similarity index 100% rename from src/components/Abstract/InitializeSensorBase_tfs.hpp rename to src/components/base_classes/InitializeSensorBase_tfs.hpp diff --git a/src/components/Abstract/ObcCommunicationBase.cpp b/src/components/base_classes/ObcCommunicationBase.cpp similarity index 100% rename from src/components/Abstract/ObcCommunicationBase.cpp rename to src/components/base_classes/ObcCommunicationBase.cpp diff --git a/src/components/Abstract/ObcCommunicationBase.h b/src/components/base_classes/ObcCommunicationBase.h similarity index 100% rename from src/components/Abstract/ObcCommunicationBase.h rename to src/components/base_classes/ObcCommunicationBase.h diff --git a/src/components/Abstract/ObcGpioBase.cpp b/src/components/base_classes/ObcGpioBase.cpp similarity index 100% rename from src/components/Abstract/ObcGpioBase.cpp rename to src/components/base_classes/ObcGpioBase.cpp diff --git a/src/components/Abstract/ObcGpioBase.h b/src/components/base_classes/ObcGpioBase.h similarity index 100% rename from src/components/Abstract/ObcGpioBase.h rename to src/components/base_classes/ObcGpioBase.h diff --git a/src/components/Abstract/ObcI2cTargetCommunicationBase.cpp b/src/components/base_classes/ObcI2cTargetCommunicationBase.cpp similarity index 100% rename from src/components/Abstract/ObcI2cTargetCommunicationBase.cpp rename to src/components/base_classes/ObcI2cTargetCommunicationBase.cpp diff --git a/src/components/Abstract/ObcI2cTargetCommunicationBase.h b/src/components/base_classes/ObcI2cTargetCommunicationBase.h similarity index 100% rename from src/components/Abstract/ObcI2cTargetCommunicationBase.h rename to src/components/base_classes/ObcI2cTargetCommunicationBase.h diff --git a/src/components/Abstract/SensorBase.h b/src/components/base_classes/SensorBase.h similarity index 100% rename from src/components/Abstract/SensorBase.h rename to src/components/base_classes/SensorBase.h diff --git a/src/components/Abstract/SensorBase_tfs.hpp b/src/components/base_classes/SensorBase_tfs.hpp similarity index 100% rename from src/components/Abstract/SensorBase_tfs.hpp rename to src/components/base_classes/SensorBase_tfs.hpp diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index e7dcafb88..68682d1a8 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -9,7 +9,7 @@ #include -#include "../Abstract/ComponentBase.h" +#include "../base_classes/ComponentBase.h" /** * @class ExampleChangeStructure diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 8379ba0ca..abc0ba023 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -5,8 +5,8 @@ #pragma once #include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/I2cControllerCommunicationBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/I2cControllerCommunicationBase.h" /** * @class ExampleI2cControllerForHils diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index ead2f338f..6b59c9dd6 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -6,8 +6,8 @@ #pragma once #include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/ObcI2cTargetCommunicationBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/ObcI2cTargetCommunicationBase.h" /** * @class ExampleI2cTargetForHils diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index e3c1e5c20..51a8ba8b4 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -5,8 +5,8 @@ #pragma once #include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/ObcCommunicationBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/ObcCommunicationBase.h" /** * @class ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index d1e5efbd4..ea28b697b 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -6,9 +6,9 @@ #pragma once #include -#include "../Abstract/ComponentBase.h" -#include "../Abstract/IGPIOCompo.h" -#include "../Abstract/ObcCommunicationBase.h" +#include "../base_classes/ComponentBase.h" +#include "../base_classes/IGPIOCompo.h" +#include "../base_classes/ObcCommunicationBase.h" /** * @class ExampleSerialCommunicationWithObc diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 621ee29a6..2f15a734b 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ #define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ -#include +#include #include diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index 672ad8fd6..5ec351247 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -8,7 +8,7 @@ #ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ #define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ -#include +#include #include #include diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/interface/sils/ports/gpio_port.hpp index 99efa06da..b6796620e 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/interface/sils/ports/gpio_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ #define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ -#include +#include #define GPIO_HIGH true #define GPIO_LOW false From 3d4432d8b03c5fa62fc449bbc7e9770407f4aaf3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:53:36 +0100 Subject: [PATCH 0279/1086] Rename AOCS --- README.md | 2 +- src/components/CMakeLists.txt | 32 +++++++++---------- .../{AOCS => aocs}/GNSSReceiver.cpp | 0 src/components/{AOCS => aocs}/GNSSReceiver.h | 0 src/components/{AOCS => aocs}/Gyro.cpp | 0 src/components/{AOCS => aocs}/Gyro.h | 0 .../{AOCS => aocs}/InitGnssReceiver.cpp | 0 .../{AOCS => aocs}/InitGnssReceiver.hpp | 2 +- src/components/{AOCS => aocs}/InitGyro.cpp | 0 src/components/{AOCS => aocs}/InitGyro.hpp | 2 +- .../{AOCS => aocs}/InitMagSensor.cpp | 0 .../{AOCS => aocs}/InitMagSensor.hpp | 2 +- .../{AOCS => aocs}/InitMagTorquer.cpp | 0 .../{AOCS => aocs}/InitMagTorquer.hpp | 2 +- src/components/{AOCS => aocs}/InitRwModel.cpp | 0 src/components/{AOCS => aocs}/InitRwModel.hpp | 2 +- src/components/{AOCS => aocs}/InitStt.cpp | 0 src/components/{AOCS => aocs}/InitStt.hpp | 2 +- .../{AOCS => aocs}/InitSunSensor.cpp | 0 .../{AOCS => aocs}/InitSunSensor.hpp | 2 +- src/components/{AOCS => aocs}/MagSensor.cpp | 0 src/components/{AOCS => aocs}/MagSensor.h | 0 src/components/{AOCS => aocs}/MagTorquer.cpp | 0 src/components/{AOCS => aocs}/MagTorquer.h | 0 src/components/{AOCS => aocs}/RWJitter.cpp | 0 src/components/{AOCS => aocs}/RWJitter.h | 0 src/components/{AOCS => aocs}/RWModel.cpp | 0 src/components/{AOCS => aocs}/RWModel.h | 0 src/components/{AOCS => aocs}/STT.cpp | 0 src/components/{AOCS => aocs}/STT.h | 0 src/components/{AOCS => aocs}/SunSensor.cpp | 0 src/components/{AOCS => aocs}/SunSensor.h | 0 src/components/{AOCS => aocs}/rw_ode.cpp | 0 src/components/{AOCS => aocs}/rw_ode.hpp | 0 .../sample_spacecraft/sample_components.hpp | 20 ++++++------ 35 files changed, 34 insertions(+), 34 deletions(-) rename src/components/{AOCS => aocs}/GNSSReceiver.cpp (100%) rename src/components/{AOCS => aocs}/GNSSReceiver.h (100%) rename src/components/{AOCS => aocs}/Gyro.cpp (100%) rename src/components/{AOCS => aocs}/Gyro.h (100%) rename src/components/{AOCS => aocs}/InitGnssReceiver.cpp (100%) rename src/components/{AOCS => aocs}/InitGnssReceiver.hpp (96%) rename src/components/{AOCS => aocs}/InitGyro.cpp (100%) rename src/components/{AOCS => aocs}/InitGyro.hpp (96%) rename src/components/{AOCS => aocs}/InitMagSensor.cpp (100%) rename src/components/{AOCS => aocs}/InitMagSensor.hpp (96%) rename src/components/{AOCS => aocs}/InitMagTorquer.cpp (100%) rename src/components/{AOCS => aocs}/InitMagTorquer.hpp (96%) rename src/components/{AOCS => aocs}/InitRwModel.cpp (100%) rename src/components/{AOCS => aocs}/InitRwModel.hpp (96%) rename src/components/{AOCS => aocs}/InitStt.cpp (100%) rename src/components/{AOCS => aocs}/InitStt.hpp (97%) rename src/components/{AOCS => aocs}/InitSunSensor.cpp (100%) rename src/components/{AOCS => aocs}/InitSunSensor.hpp (96%) rename src/components/{AOCS => aocs}/MagSensor.cpp (100%) rename src/components/{AOCS => aocs}/MagSensor.h (100%) rename src/components/{AOCS => aocs}/MagTorquer.cpp (100%) rename src/components/{AOCS => aocs}/MagTorquer.h (100%) rename src/components/{AOCS => aocs}/RWJitter.cpp (100%) rename src/components/{AOCS => aocs}/RWJitter.h (100%) rename src/components/{AOCS => aocs}/RWModel.cpp (100%) rename src/components/{AOCS => aocs}/RWModel.h (100%) rename src/components/{AOCS => aocs}/STT.cpp (100%) rename src/components/{AOCS => aocs}/STT.h (100%) rename src/components/{AOCS => aocs}/SunSensor.cpp (100%) rename src/components/{AOCS => aocs}/SunSensor.h (100%) rename src/components/{AOCS => aocs}/rw_ode.cpp (100%) rename src/components/{AOCS => aocs}/rw_ode.hpp (100%) diff --git a/README.md b/README.md index ec8430d76..dbb69b235 100644 --- a/README.md +++ b/README.md @@ -95,5 +95,5 @@ ## Publications -1. S. Ikari, and et al., "Development of Compact and Highly Capable Integrated AOCS Module for CubeSats", [2022-f-41](https://archive.ists.ne.jp/upload_pdf/F-9-05.pdf), 33rd ISTS, 2022. +1. S. Ikari, and et al., "Development of Compact and Highly Capable Integrated aocs Module for CubeSats", [2022-f-41](https://archive.ists.ne.jp/upload_pdf/F-9-05.pdf), 33rd ISTS, 2022. 1. 五十里, 他, "宇宙開発の効率化・高度化を目指した東京大学中須賀・船瀬研のOSS活動", [UNISEC2022-04](http://unisec.jp/archives/7836), 12th UNISEC Space Takumi Conference, 2022. diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index cfc19a38a..9cb4bdf8d 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -8,22 +8,22 @@ add_library(${PROJECT_NAME} STATIC base_classes/ObcI2cTargetCommunicationBase.cpp base_classes/ObcGpioBase.cpp - AOCS/Gyro.cpp - AOCS/InitGyro.cpp - AOCS/MagSensor.cpp - AOCS/InitMagSensor.cpp - AOCS/MagTorquer.cpp - AOCS/InitMagTorquer.cpp - AOCS/rw_ode.cpp - AOCS/RWModel.cpp - AOCS/InitRwModel.cpp - AOCS/RWJitter.cpp - AOCS/STT.cpp - AOCS/InitStt.cpp - AOCS/SunSensor.cpp - AOCS/InitSunSensor.cpp - AOCS/GNSSReceiver.cpp - AOCS/InitGnssReceiver.cpp + aocs/Gyro.cpp + aocs/InitGyro.cpp + aocs/MagSensor.cpp + aocs/InitMagSensor.cpp + aocs/MagTorquer.cpp + aocs/InitMagTorquer.cpp + aocs/rw_ode.cpp + aocs/RWModel.cpp + aocs/InitRwModel.cpp + aocs/RWJitter.cpp + aocs/STT.cpp + aocs/InitStt.cpp + aocs/SunSensor.cpp + aocs/InitSunSensor.cpp + aocs/GNSSReceiver.cpp + aocs/InitGnssReceiver.cpp CDH/OBC.cpp CDH/OBC_C2A.cpp diff --git a/src/components/AOCS/GNSSReceiver.cpp b/src/components/aocs/GNSSReceiver.cpp similarity index 100% rename from src/components/AOCS/GNSSReceiver.cpp rename to src/components/aocs/GNSSReceiver.cpp diff --git a/src/components/AOCS/GNSSReceiver.h b/src/components/aocs/GNSSReceiver.h similarity index 100% rename from src/components/AOCS/GNSSReceiver.h rename to src/components/aocs/GNSSReceiver.h diff --git a/src/components/AOCS/Gyro.cpp b/src/components/aocs/Gyro.cpp similarity index 100% rename from src/components/AOCS/Gyro.cpp rename to src/components/aocs/Gyro.cpp diff --git a/src/components/AOCS/Gyro.h b/src/components/aocs/Gyro.h similarity index 100% rename from src/components/AOCS/Gyro.h rename to src/components/aocs/Gyro.h diff --git a/src/components/AOCS/InitGnssReceiver.cpp b/src/components/aocs/InitGnssReceiver.cpp similarity index 100% rename from src/components/AOCS/InitGnssReceiver.cpp rename to src/components/aocs/InitGnssReceiver.cpp diff --git a/src/components/AOCS/InitGnssReceiver.hpp b/src/components/aocs/InitGnssReceiver.hpp similarity index 96% rename from src/components/AOCS/InitGnssReceiver.hpp rename to src/components/aocs/InitGnssReceiver.hpp index 5f3e1d91f..c339d5dce 100644 --- a/src/components/AOCS/InitGnssReceiver.hpp +++ b/src/components/aocs/InitGnssReceiver.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGNSSReceiver diff --git a/src/components/AOCS/InitGyro.cpp b/src/components/aocs/InitGyro.cpp similarity index 100% rename from src/components/AOCS/InitGyro.cpp rename to src/components/aocs/InitGyro.cpp diff --git a/src/components/AOCS/InitGyro.hpp b/src/components/aocs/InitGyro.hpp similarity index 96% rename from src/components/AOCS/InitGyro.hpp rename to src/components/aocs/InitGyro.hpp index 6f7be6ad8..c5407152c 100644 --- a/src/components/AOCS/InitGyro.hpp +++ b/src/components/aocs/InitGyro.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGyro diff --git a/src/components/AOCS/InitMagSensor.cpp b/src/components/aocs/InitMagSensor.cpp similarity index 100% rename from src/components/AOCS/InitMagSensor.cpp rename to src/components/aocs/InitMagSensor.cpp diff --git a/src/components/AOCS/InitMagSensor.hpp b/src/components/aocs/InitMagSensor.hpp similarity index 96% rename from src/components/AOCS/InitMagSensor.hpp rename to src/components/aocs/InitMagSensor.hpp index 4f3ca4124..f4a29dcc2 100644 --- a/src/components/AOCS/InitMagSensor.hpp +++ b/src/components/aocs/InitMagSensor.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitMagSensor diff --git a/src/components/AOCS/InitMagTorquer.cpp b/src/components/aocs/InitMagTorquer.cpp similarity index 100% rename from src/components/AOCS/InitMagTorquer.cpp rename to src/components/aocs/InitMagTorquer.cpp diff --git a/src/components/AOCS/InitMagTorquer.hpp b/src/components/aocs/InitMagTorquer.hpp similarity index 96% rename from src/components/AOCS/InitMagTorquer.hpp rename to src/components/aocs/InitMagTorquer.hpp index 1de7356b6..e277fc0bf 100644 --- a/src/components/AOCS/InitMagTorquer.hpp +++ b/src/components/aocs/InitMagTorquer.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitMagTorquer diff --git a/src/components/AOCS/InitRwModel.cpp b/src/components/aocs/InitRwModel.cpp similarity index 100% rename from src/components/AOCS/InitRwModel.cpp rename to src/components/aocs/InitRwModel.cpp diff --git a/src/components/AOCS/InitRwModel.hpp b/src/components/aocs/InitRwModel.hpp similarity index 96% rename from src/components/AOCS/InitRwModel.hpp rename to src/components/aocs/InitRwModel.hpp index dc93bc2d5..e3b14a677 100644 --- a/src/components/AOCS/InitRwModel.hpp +++ b/src/components/aocs/InitRwModel.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitRWModel diff --git a/src/components/AOCS/InitStt.cpp b/src/components/aocs/InitStt.cpp similarity index 100% rename from src/components/AOCS/InitStt.cpp rename to src/components/aocs/InitStt.cpp diff --git a/src/components/AOCS/InitStt.hpp b/src/components/aocs/InitStt.hpp similarity index 97% rename from src/components/AOCS/InitStt.hpp rename to src/components/aocs/InitStt.hpp index 2cd47a6c7..705e96e84 100644 --- a/src/components/AOCS/InitStt.hpp +++ b/src/components/aocs/InitStt.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /** * @fn InitSTT diff --git a/src/components/AOCS/InitSunSensor.cpp b/src/components/aocs/InitSunSensor.cpp similarity index 100% rename from src/components/AOCS/InitSunSensor.cpp rename to src/components/aocs/InitSunSensor.cpp diff --git a/src/components/AOCS/InitSunSensor.hpp b/src/components/aocs/InitSunSensor.hpp similarity index 96% rename from src/components/AOCS/InitSunSensor.hpp rename to src/components/aocs/InitSunSensor.hpp index ee19e139a..bda3602d3 100644 --- a/src/components/AOCS/InitSunSensor.hpp +++ b/src/components/aocs/InitSunSensor.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitSunSensor diff --git a/src/components/AOCS/MagSensor.cpp b/src/components/aocs/MagSensor.cpp similarity index 100% rename from src/components/AOCS/MagSensor.cpp rename to src/components/aocs/MagSensor.cpp diff --git a/src/components/AOCS/MagSensor.h b/src/components/aocs/MagSensor.h similarity index 100% rename from src/components/AOCS/MagSensor.h rename to src/components/aocs/MagSensor.h diff --git a/src/components/AOCS/MagTorquer.cpp b/src/components/aocs/MagTorquer.cpp similarity index 100% rename from src/components/AOCS/MagTorquer.cpp rename to src/components/aocs/MagTorquer.cpp diff --git a/src/components/AOCS/MagTorquer.h b/src/components/aocs/MagTorquer.h similarity index 100% rename from src/components/AOCS/MagTorquer.h rename to src/components/aocs/MagTorquer.h diff --git a/src/components/AOCS/RWJitter.cpp b/src/components/aocs/RWJitter.cpp similarity index 100% rename from src/components/AOCS/RWJitter.cpp rename to src/components/aocs/RWJitter.cpp diff --git a/src/components/AOCS/RWJitter.h b/src/components/aocs/RWJitter.h similarity index 100% rename from src/components/AOCS/RWJitter.h rename to src/components/aocs/RWJitter.h diff --git a/src/components/AOCS/RWModel.cpp b/src/components/aocs/RWModel.cpp similarity index 100% rename from src/components/AOCS/RWModel.cpp rename to src/components/aocs/RWModel.cpp diff --git a/src/components/AOCS/RWModel.h b/src/components/aocs/RWModel.h similarity index 100% rename from src/components/AOCS/RWModel.h rename to src/components/aocs/RWModel.h diff --git a/src/components/AOCS/STT.cpp b/src/components/aocs/STT.cpp similarity index 100% rename from src/components/AOCS/STT.cpp rename to src/components/aocs/STT.cpp diff --git a/src/components/AOCS/STT.h b/src/components/aocs/STT.h similarity index 100% rename from src/components/AOCS/STT.h rename to src/components/aocs/STT.h diff --git a/src/components/AOCS/SunSensor.cpp b/src/components/aocs/SunSensor.cpp similarity index 100% rename from src/components/AOCS/SunSensor.cpp rename to src/components/aocs/SunSensor.cpp diff --git a/src/components/AOCS/SunSensor.h b/src/components/aocs/SunSensor.h similarity index 100% rename from src/components/AOCS/SunSensor.h rename to src/components/aocs/SunSensor.h diff --git a/src/components/AOCS/rw_ode.cpp b/src/components/aocs/rw_ode.cpp similarity index 100% rename from src/components/AOCS/rw_ode.cpp rename to src/components/aocs/rw_ode.cpp diff --git a/src/components/AOCS/rw_ode.hpp b/src/components/aocs/rw_ode.hpp similarity index 100% rename from src/components/AOCS/rw_ode.hpp rename to src/components/aocs/rw_ode.hpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 0026bf210..e64561a11 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -8,25 +8,25 @@ #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include #include #include #include #include +#include +#include +#include +#include +#include +#include +#include #include #include #include #include -#include +#include +#include #include #include "../installed_components.hpp" From b16c7acace276e6eea563af48ba6c0eb00799cd7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:56:23 +0100 Subject: [PATCH 0280/1086] Rename CDH --- src/components/CMakeLists.txt | 7 ++----- src/components/aocs/Gyro.cpp | 2 +- src/components/base_classes/ObcCommunicationBase.h | 2 +- src/components/base_classes/ObcGpioBase.h | 2 +- .../base_classes/ObcI2cTargetCommunicationBase.h | 2 +- src/components/{CDH => cdh}/OBC.cpp | 0 src/components/{CDH => cdh}/OBC.h | 0 src/components/{CDH => cdh}/OBC_C2A.cpp | 0 src/components/{CDH => cdh}/OBC_C2A.h | 0 .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 10 files changed, 7 insertions(+), 10 deletions(-) rename src/components/{CDH => cdh}/OBC.cpp (100%) rename src/components/{CDH => cdh}/OBC.h (100%) rename src/components/{CDH => cdh}/OBC_C2A.cpp (100%) rename src/components/{CDH => cdh}/OBC_C2A.h (100%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 9cb4bdf8d..1d20f26c4 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -25,8 +25,8 @@ add_library(${PROJECT_NAME} STATIC aocs/GNSSReceiver.cpp aocs/InitGnssReceiver.cpp - CDH/OBC.cpp - CDH/OBC_C2A.cpp + cdh/OBC.cpp + cdh/OBC_C2A.cpp CommGS/Antenna.cpp CommGS/AntennaRadiationPattern.cpp @@ -60,9 +60,6 @@ add_library(${PROJECT_NAME} STATIC Propulsion/SimpleThruster.cpp Propulsion/InitSimpleThruster.cpp - -## C++/CLI related codes -# CDH/TMTCInterface.cpp ) include(../../common.cmake) diff --git a/src/components/aocs/Gyro.cpp b/src/components/aocs/Gyro.cpp index c23ddaa9d..15fc19a8d 100644 --- a/src/components/aocs/Gyro.cpp +++ b/src/components/aocs/Gyro.cpp @@ -5,7 +5,7 @@ #include "Gyro.h" -#include "../CDH/OBC_C2A.h" +#include "../cdh/OBC_C2A.h" Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) diff --git a/src/components/base_classes/ObcCommunicationBase.h b/src/components/base_classes/ObcCommunicationBase.h index a3421082b..f70cddd99 100644 --- a/src/components/base_classes/ObcCommunicationBase.h +++ b/src/components/base_classes/ObcCommunicationBase.h @@ -5,7 +5,7 @@ #pragma once #include -#include "../CDH/OBC.h" +#include "../cdh/OBC.h" /** * @enum OBC_COM_UART_MODE diff --git a/src/components/base_classes/ObcGpioBase.h b/src/components/base_classes/ObcGpioBase.h index 5b6d4e648..067ea8929 100644 --- a/src/components/base_classes/ObcGpioBase.h +++ b/src/components/base_classes/ObcGpioBase.h @@ -4,7 +4,7 @@ * TODO: consider relation with IGPIOCompo */ #pragma once -#include "../CDH/OBC.h" +#include "../cdh/OBC.h" /** * @class ObcGpioBase diff --git a/src/components/base_classes/ObcI2cTargetCommunicationBase.h b/src/components/base_classes/ObcI2cTargetCommunicationBase.h index 69888329a..d5e86d6c5 100644 --- a/src/components/base_classes/ObcI2cTargetCommunicationBase.h +++ b/src/components/base_classes/ObcI2cTargetCommunicationBase.h @@ -4,7 +4,7 @@ */ #pragma once #include "../../interface/hils/hils_port_manager.hpp" -#include "../CDH/OBC.h" +#include "../cdh/OBC.h" #include "ObcCommunicationBase.h" /** diff --git a/src/components/CDH/OBC.cpp b/src/components/cdh/OBC.cpp similarity index 100% rename from src/components/CDH/OBC.cpp rename to src/components/cdh/OBC.cpp diff --git a/src/components/CDH/OBC.h b/src/components/cdh/OBC.h similarity index 100% rename from src/components/CDH/OBC.h rename to src/components/cdh/OBC.h diff --git a/src/components/CDH/OBC_C2A.cpp b/src/components/cdh/OBC_C2A.cpp similarity index 100% rename from src/components/CDH/OBC_C2A.cpp rename to src/components/cdh/OBC_C2A.cpp diff --git a/src/components/CDH/OBC_C2A.h b/src/components/cdh/OBC_C2A.h similarity index 100% rename from src/components/CDH/OBC_C2A.h rename to src/components/cdh/OBC_C2A.h diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index e64561a11..c12fa609f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include +#include #include #include From 990a3d587152d4793546be32bce04fc14ed60fae Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 10:57:09 +0100 Subject: [PATCH 0281/1086] Rename CommGS --- src/components/CMakeLists.txt | 10 +++++----- src/components/{CommGS => communication}/Antenna.cpp | 0 src/components/{CommGS => communication}/Antenna.hpp | 0 .../AntennaRadiationPattern.cpp | 0 .../AntennaRadiationPattern.hpp | 0 .../{CommGS => communication}/GScalculator.cpp | 0 .../{CommGS => communication}/GScalculator.h | 2 +- .../{CommGS => communication}/InitAntenna.cpp | 0 .../{CommGS => communication}/InitAntenna.hpp | 2 +- .../{CommGS => communication}/InitGsCalculator.cpp | 0 .../{CommGS => communication}/InitGsCalculator.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 4 ++-- .../sample_ground_station_components.hpp | 4 ++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 14 files changed, 13 insertions(+), 13 deletions(-) rename src/components/{CommGS => communication}/Antenna.cpp (100%) rename src/components/{CommGS => communication}/Antenna.hpp (100%) rename src/components/{CommGS => communication}/AntennaRadiationPattern.cpp (100%) rename src/components/{CommGS => communication}/AntennaRadiationPattern.hpp (100%) rename src/components/{CommGS => communication}/GScalculator.cpp (100%) rename src/components/{CommGS => communication}/GScalculator.h (99%) rename src/components/{CommGS => communication}/InitAntenna.cpp (100%) rename src/components/{CommGS => communication}/InitAntenna.hpp (86%) rename src/components/{CommGS => communication}/InitGsCalculator.cpp (100%) rename src/components/{CommGS => communication}/InitGsCalculator.hpp (85%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 1d20f26c4..07f8bd93e 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -28,11 +28,11 @@ add_library(${PROJECT_NAME} STATIC cdh/OBC.cpp cdh/OBC_C2A.cpp - CommGS/Antenna.cpp - CommGS/AntennaRadiationPattern.cpp - CommGS/InitAntenna.cpp - CommGS/GScalculator.cpp - CommGS/InitGsCalculator.cpp + communication/Antenna.cpp + communication/AntennaRadiationPattern.cpp + communication/InitAntenna.cpp + communication/GScalculator.cpp + communication/InitGsCalculator.cpp examples/example_change_structure.cpp examples/example_serial_communication_with_obc.cpp diff --git a/src/components/CommGS/Antenna.cpp b/src/components/communication/Antenna.cpp similarity index 100% rename from src/components/CommGS/Antenna.cpp rename to src/components/communication/Antenna.cpp diff --git a/src/components/CommGS/Antenna.hpp b/src/components/communication/Antenna.hpp similarity index 100% rename from src/components/CommGS/Antenna.hpp rename to src/components/communication/Antenna.hpp diff --git a/src/components/CommGS/AntennaRadiationPattern.cpp b/src/components/communication/AntennaRadiationPattern.cpp similarity index 100% rename from src/components/CommGS/AntennaRadiationPattern.cpp rename to src/components/communication/AntennaRadiationPattern.cpp diff --git a/src/components/CommGS/AntennaRadiationPattern.hpp b/src/components/communication/AntennaRadiationPattern.hpp similarity index 100% rename from src/components/CommGS/AntennaRadiationPattern.hpp rename to src/components/communication/AntennaRadiationPattern.hpp diff --git a/src/components/CommGS/GScalculator.cpp b/src/components/communication/GScalculator.cpp similarity index 100% rename from src/components/CommGS/GScalculator.cpp rename to src/components/communication/GScalculator.cpp diff --git a/src/components/CommGS/GScalculator.h b/src/components/communication/GScalculator.h similarity index 99% rename from src/components/CommGS/GScalculator.h rename to src/components/communication/GScalculator.h index f59cd0d6d..163e00eca 100644 --- a/src/components/CommGS/GScalculator.h +++ b/src/components/communication/GScalculator.h @@ -8,7 +8,7 @@ #include -#include +#include #include #include #include diff --git a/src/components/CommGS/InitAntenna.cpp b/src/components/communication/InitAntenna.cpp similarity index 100% rename from src/components/CommGS/InitAntenna.cpp rename to src/components/communication/InitAntenna.cpp diff --git a/src/components/CommGS/InitAntenna.hpp b/src/components/communication/InitAntenna.hpp similarity index 86% rename from src/components/CommGS/InitAntenna.hpp rename to src/components/communication/InitAntenna.hpp index 2542de7d5..748361199 100644 --- a/src/components/CommGS/InitAntenna.hpp +++ b/src/components/communication/InitAntenna.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitAntenna diff --git a/src/components/CommGS/InitGsCalculator.cpp b/src/components/communication/InitGsCalculator.cpp similarity index 100% rename from src/components/CommGS/InitGsCalculator.cpp rename to src/components/communication/InitGsCalculator.cpp diff --git a/src/components/CommGS/InitGsCalculator.hpp b/src/components/communication/InitGsCalculator.hpp similarity index 85% rename from src/components/CommGS/InitGsCalculator.hpp rename to src/components/communication/InitGsCalculator.hpp index a086434dc..108dbed23 100644 --- a/src/components/CommGS/InitGsCalculator.hpp +++ b/src/components/communication/InitGsCalculator.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /* * @fn InitGscalculator diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index c4108b7b6..bcd49d668 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ -#include +#include -#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 1865fc6f6..85c1ab70f 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ -#include -#include +#include +#include /** * @class SampleGSComponents diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index c12fa609f..3ae1e6403 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -10,7 +10,7 @@ #include #include -#include +#include #include #include #include From 77d69ba3e40f267f34477522a52aecfb82aabb8d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:02:59 +0100 Subject: [PATCH 0282/1086] Rename IdealComponents --- src/components/CMakeLists.txt | 8 ++++---- .../ForceGenerator.cpp | 0 .../ForceGenerator.hpp | 0 .../InitializeForceGenerator.cpp | 0 .../InitializeForceGenerator.hpp | 0 .../InitializeTorqueGenerator.cpp | 0 .../InitializeTorqueGenerator.hpp | 0 .../TorqueGenerator.cpp | 0 .../TorqueGenerator.hpp | 0 .../spacecraft/sample_spacecraft/sample_components.hpp | 4 ++-- 10 files changed, 6 insertions(+), 6 deletions(-) rename src/components/{IdealComponents => ideal_components}/ForceGenerator.cpp (100%) rename src/components/{IdealComponents => ideal_components}/ForceGenerator.hpp (100%) rename src/components/{IdealComponents => ideal_components}/InitializeForceGenerator.cpp (100%) rename src/components/{IdealComponents => ideal_components}/InitializeForceGenerator.hpp (100%) rename src/components/{IdealComponents => ideal_components}/InitializeTorqueGenerator.cpp (100%) rename src/components/{IdealComponents => ideal_components}/InitializeTorqueGenerator.hpp (100%) rename src/components/{IdealComponents => ideal_components}/TorqueGenerator.cpp (100%) rename src/components/{IdealComponents => ideal_components}/TorqueGenerator.hpp (100%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 07f8bd93e..931a22c05 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -40,10 +40,10 @@ add_library(${PROJECT_NAME} STATIC examples/example_i2c_controller_for_hils.cpp examples/example_i2c_target_for_hils.cpp - IdealComponents/ForceGenerator.cpp - IdealComponents/InitializeForceGenerator.cpp - IdealComponents/TorqueGenerator.cpp - IdealComponents/InitializeTorqueGenerator.cpp + ideal_components/ForceGenerator.cpp + ideal_components/InitializeForceGenerator.cpp + ideal_components/TorqueGenerator.cpp + ideal_components/InitializeTorqueGenerator.cpp Mission/Telescope/Telescope.cpp Mission/Telescope/InitTelescope.cpp diff --git a/src/components/IdealComponents/ForceGenerator.cpp b/src/components/ideal_components/ForceGenerator.cpp similarity index 100% rename from src/components/IdealComponents/ForceGenerator.cpp rename to src/components/ideal_components/ForceGenerator.cpp diff --git a/src/components/IdealComponents/ForceGenerator.hpp b/src/components/ideal_components/ForceGenerator.hpp similarity index 100% rename from src/components/IdealComponents/ForceGenerator.hpp rename to src/components/ideal_components/ForceGenerator.hpp diff --git a/src/components/IdealComponents/InitializeForceGenerator.cpp b/src/components/ideal_components/InitializeForceGenerator.cpp similarity index 100% rename from src/components/IdealComponents/InitializeForceGenerator.cpp rename to src/components/ideal_components/InitializeForceGenerator.cpp diff --git a/src/components/IdealComponents/InitializeForceGenerator.hpp b/src/components/ideal_components/InitializeForceGenerator.hpp similarity index 100% rename from src/components/IdealComponents/InitializeForceGenerator.hpp rename to src/components/ideal_components/InitializeForceGenerator.hpp diff --git a/src/components/IdealComponents/InitializeTorqueGenerator.cpp b/src/components/ideal_components/InitializeTorqueGenerator.cpp similarity index 100% rename from src/components/IdealComponents/InitializeTorqueGenerator.cpp rename to src/components/ideal_components/InitializeTorqueGenerator.cpp diff --git a/src/components/IdealComponents/InitializeTorqueGenerator.hpp b/src/components/ideal_components/InitializeTorqueGenerator.hpp similarity index 100% rename from src/components/IdealComponents/InitializeTorqueGenerator.hpp rename to src/components/ideal_components/InitializeTorqueGenerator.hpp diff --git a/src/components/IdealComponents/TorqueGenerator.cpp b/src/components/ideal_components/TorqueGenerator.cpp similarity index 100% rename from src/components/IdealComponents/TorqueGenerator.cpp rename to src/components/ideal_components/TorqueGenerator.cpp diff --git a/src/components/IdealComponents/TorqueGenerator.hpp b/src/components/ideal_components/TorqueGenerator.hpp similarity index 100% rename from src/components/IdealComponents/TorqueGenerator.hpp rename to src/components/ideal_components/TorqueGenerator.hpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 3ae1e6403..f604f589e 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -11,8 +11,8 @@ #include #include -#include -#include +#include +#include #include #include #include From 424c9545e06d76c92dbd086e15e09674162e9c2c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:05:16 +0100 Subject: [PATCH 0283/1086] Rename Mission/Telescope --- src/components/CMakeLists.txt | 4 +- .../Mission/Telescope/InitTelescope.cpp | 54 ----- .../Mission/Telescope/InitTelescope.hpp | 20 -- .../Mission/Telescope/Telescope.cpp | 202 ------------------ src/components/Mission/Telescope/Telescope.h | 123 ----------- 5 files changed, 2 insertions(+), 401 deletions(-) delete mode 100644 src/components/Mission/Telescope/InitTelescope.cpp delete mode 100644 src/components/Mission/Telescope/InitTelescope.hpp delete mode 100644 src/components/Mission/Telescope/Telescope.cpp delete mode 100644 src/components/Mission/Telescope/Telescope.h diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 931a22c05..b86e787b6 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -45,8 +45,8 @@ add_library(${PROJECT_NAME} STATIC ideal_components/TorqueGenerator.cpp ideal_components/InitializeTorqueGenerator.cpp - Mission/Telescope/Telescope.cpp - Mission/Telescope/InitTelescope.cpp + mission/Telescope.cpp + mission/InitTelescope.cpp Power/PCU.cpp Power/BAT.cpp diff --git a/src/components/Mission/Telescope/InitTelescope.cpp b/src/components/Mission/Telescope/InitTelescope.cpp deleted file mode 100644 index 8e76caec1..000000000 --- a/src/components/Mission/Telescope/InitTelescope.cpp +++ /dev/null @@ -1,54 +0,0 @@ -/* - * @file InitTelescope.cpp - * @brief Initialize function of Telescope - */ - -#include "InitTelescope.hpp" - -#include - -#include - -#include "interface/initialize/initialize_file_access.hpp" - -using namespace std; - -Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info) { - using libra::pi; - - IniAccess Telescope_conf(fname); - const string st_sensor_id = std::to_string(static_cast(sensor_id)); - const char* cs = st_sensor_id.data(); - - char TelescopeSection[30] = "TELESCOPE_"; -#ifdef WIN32 - strcat_s(TelescopeSection, cs); -#else - strcat(TelescopeSection, cs); -#endif - - Quaternion q_b2c; - Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", q_b2c); - - double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_exclusion_angle_deg"); - double sun_forbidden_angle_rad = sun_forbidden_angle_deg * pi / 180; // deg to rad - double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_exclusion_angle_deg"); - double earth_forbidden_angle_rad = earth_forbidden_angle_deg * pi / 180; // deg to rad - double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_exclusion_angle_deg"); - double moon_forbidden_angle_rad = moon_forbidden_angle_deg * pi / 180; // deg to rad - - int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); - int y_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_number_of_pixel"); - - double x_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_deg_per_pixel"); - double x_fov_par_pix_rad = x_fov_par_pix_deg * pi / 180; // deg to rad - double y_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_deg_per_pixel"); - double y_fov_par_pix_rad = y_fov_par_pix_deg * pi / 180; // deg to rad - - int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); - - Telescope telescope(clock_gen, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, y_num_of_pix, - x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); - return telescope; -} diff --git a/src/components/Mission/Telescope/InitTelescope.hpp b/src/components/Mission/Telescope/InitTelescope.hpp deleted file mode 100644 index 9daed1c85..000000000 --- a/src/components/Mission/Telescope/InitTelescope.hpp +++ /dev/null @@ -1,20 +0,0 @@ -/* - * @file InitTelescope.hpp - * @brief Initialize function of Telescope - */ -#pragma once - -#include - -/* - * @fn InitTelescope - * @brief Initialize function of Telescope - * @param [in] clock_gen: Clock generator - * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to initialize file - * @param [in] attitude: Attitude information - * @param [in] hipp: Star information by Hipparcos catalogue - * @param [in] local_celes_info: Local celestial information - */ -Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info); diff --git a/src/components/Mission/Telescope/Telescope.cpp b/src/components/Mission/Telescope/Telescope.cpp deleted file mode 100644 index c100cd68d..000000000 --- a/src/components/Mission/Telescope/Telescope.cpp +++ /dev/null @@ -1,202 +0,0 @@ -/* - * @file Telescope.cpp - * @brief Component emulation: Telescope - */ - -#include "Telescope.h" - -#include -#include - -using namespace std; -using namespace libra; - -Telescope::Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, - double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, - size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info) - : ComponentBase(1, clock_gen), - q_b2c_(q_b2c), - sun_forbidden_angle_(sun_forbidden_angle), - earth_forbidden_angle_(earth_forbidden_angle), - moon_forbidden_angle_(moon_forbidden_angle), - x_num_of_pix_(x_num_of_pix), - y_num_of_pix_(y_num_of_pix), - x_fov_par_pix_(x_fov_par_pix), - y_fov_par_pix_(y_fov_par_pix), - num_of_logged_stars_(num_of_logged_stars), - attitude_(attitude), - hipp_(hipp), - local_celes_info_(local_celes_info) { - is_sun_in_forbidden_angle = true; - is_earth_in_forbidden_angle = true; - is_moon_in_forbidden_angle = true; - - x_field_of_view_rad = x_num_of_pix_ * x_fov_par_pix_; - y_field_of_view_rad = y_num_of_pix_ * y_fov_par_pix_; - assert(x_field_of_view_rad < libra::pi_2); // Avoid the case that the field of view is over 90 degrees - assert(y_field_of_view_rad < libra::pi_2); - - sight_ = Vector<3>(0); - sight_[0] = 1; // (1,0,0) at component frame, Sight direction vector - - // Set 0 when t=0 - for (size_t i = 0; i < num_of_logged_stars_; i++) { - Star star; - star.hipdata.hip_num = -1; - star.hipdata.vmag = -1; - star.hipdata.ra = -1; - star.hipdata.de = -1; - star.pos_imgsensor[0] = -1; - star.pos_imgsensor[1] = -1; - - star_in_sight.push_back(star); - } -} - -Telescope::~Telescope() {} - -void Telescope::MainRoutine(int count) { - UNUSED(count); - // Check forbidden angle - is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("SUN"), sun_forbidden_angle_); - is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("EARTH"), earth_forbidden_angle_); - is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("MOON"), moon_forbidden_angle_); - // Position calculation of celestial bodies from CelesInfo - Observe(sun_pos_imgsensor, local_celes_info_->GetPosFromSC_b("SUN")); - Observe(earth_pos_imgsensor, local_celes_info_->GetPosFromSC_b("EARTH")); - Observe(moon_pos_imgsensor, local_celes_info_->GetPosFromSC_b("MOON")); - // Position calculation of stars from Hipparcos Catalogue - // No update when Hipparocos Catalogue was not readed - if (hipp_->IsCalcEnabled) ObserveStars(); - // Debug ****************************************************************** - // sun_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("SUN")); - // earth_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("EARTH")); - // moon_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("MOON")); - // angle_sun = angle(sight_, sun_pos_c) * 180/libra::pi; - // angle_earth = angle(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = angle(sight_, moon_pos_c) * 180 / libra::pi; - //****************************************************************************** -} - -bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { - Quaternion q_c2b = q_b2c_.conjugate(); - Vector<3> sight_b = q_c2b.frame_conv(sight_); - double angle_rad = libra::angle(target_b, sight_b); - if (angle_rad < forbidden_angle) { - return true; - } else - return false; -} - -void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b) { - Vector<3, double> target_c = q_b2c_.frame_conv(target_b); - double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame - double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame - - if (abs(arg_x) < x_field_of_view_rad && abs(arg_y) < y_field_of_view_rad) { - pos_imgsensor[0] = x_num_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2; - pos_imgsensor[1] = y_num_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2; - } else { // Return -1 when the body is in the out of FoV - pos_imgsensor[0] = -1; - pos_imgsensor[1] = -1; - } -} - -void Telescope::ObserveStars() { - Quaternion q_i2b = attitude_->GetQuaternion_i2b(); - - star_in_sight.clear(); // Clear first - int count = 0; // Counter for while loop - - while (star_in_sight.size() < num_of_logged_stars_) { - Vector<3> target_b = hipp_->GetStarDir_b(count, q_i2b); - Vector<3> target_c = q_b2c_.frame_conv(target_b); - - double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame - double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame - - if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { - Star star; - star.hipdata.hip_num = hipp_->GetHipID(count); - star.hipdata.vmag = hipp_->GetVmag(count); - star.hipdata.ra = hipp_->GetRA(count); - star.hipdata.de = hipp_->GetDE(count); - star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; - star.pos_imgsensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; - - star_in_sight.push_back(star); - } - - count++; - - // If read all catalogue, fill -1 and break the loop - if (count >= hipp_->GetCatalogueSize()) { - while (star_in_sight.size() < num_of_logged_stars_) { - Star star; - star.hipdata.hip_num = -1; - star.hipdata.vmag = -1; - star.hipdata.ra = -1; - star.hipdata.de = -1; - star.pos_imgsensor[0] = -1; - star.pos_imgsensor[1] = -1; - - star_in_sight.push_back(star); - } - - break; - } - } -} - -string Telescope::GetLogHeader() const { - string str_tmp = ""; - - std::string component_name = "telescope_"; - - str_tmp += WriteScalar(component_name + "sun_in_exclusion_angle", ""); - str_tmp += WriteScalar(component_name + "earth_in_exclusion_angle", ""); - str_tmp += WriteScalar(component_name + "moon_in_exclusion_angle", ""); - str_tmp += WriteVector(component_name + "sun_position", "img", "pix", 2); - str_tmp += WriteVector(component_name + "earth_position", "img", "pix", 2); - str_tmp += WriteVector(component_name + "moon_position", "img", "pix", 2); - // When Hipparcos Catalogue was not read, no output of ObserveStars - if (hipp_->IsCalcEnabled) { - for (size_t i = 0; i < num_of_logged_stars_; i++) { - str_tmp += WriteScalar(component_name + "hipparcos_id (" + to_string(i) + ")", " "); - str_tmp += WriteScalar(component_name + "visible_magnitude (" + to_string(i) + ")", " "); - str_tmp += WriteVector(component_name + "star_position (" + to_string(i) + ")", "img", "pix", 2); - } - } - - // Debug output ********************************************** - // str_tmp += WriteScalar("angle_sun", ""); - // str_tmp += WriteScalar("angle_earth", ""); - // str_tmp += WriteScalar("angle_moon", ""); - //********************************************************** - return str_tmp; -} - -string Telescope::GetLogValue() const { - string str_tmp = ""; - str_tmp += WriteScalar(is_sun_in_forbidden_angle); - str_tmp += WriteScalar(is_earth_in_forbidden_angle); - str_tmp += WriteScalar(is_moon_in_forbidden_angle); - str_tmp += WriteVector(sun_pos_imgsensor); - str_tmp += WriteVector(earth_pos_imgsensor); - str_tmp += WriteVector(moon_pos_imgsensor); - // When Hipparcos Catalogue was not read, no output of ObserveStars - if (hipp_->IsCalcEnabled) { - for (size_t i = 0; i < num_of_logged_stars_; i++) { - str_tmp += WriteScalar(star_in_sight[i].hipdata.hip_num); - str_tmp += WriteScalar(star_in_sight[i].hipdata.vmag); - str_tmp += WriteVector(star_in_sight[i].pos_imgsensor); - } - } - - // Debug output ********************************************** - // str_tmp += WriteScalar(angle_sun); - // str_tmp += WriteScalar(angle_earth); - // str_tmp += WriteScalar(angle_moon); - //********************************************************** - return str_tmp; -} diff --git a/src/components/Mission/Telescope/Telescope.h b/src/components/Mission/Telescope/Telescope.h deleted file mode 100644 index 83640524e..000000000 --- a/src/components/Mission/Telescope/Telescope.h +++ /dev/null @@ -1,123 +0,0 @@ -/* - * @file Telescope.h - * @brief Component emulation: Telescope - */ - -#pragma once -#include -#include - -#include -#include -#include -#include -#include -#include - -/* - * @struct Star - * @brief Information of stars in the telescope's field of view - */ -struct Star { - HipData hipdata; //!< Hipparcos data - libra::Vector<2> pos_imgsensor; //!< Position of image sensor -}; - -/* - * @class Telescope - * @brief Component emulation: Telescope - */ -class Telescope : public ComponentBase, public ILoggable { - public: - Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, - double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, - const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); - - ~Telescope(); - - // Getter - inline bool GetIsSunInForbiddenAngle() const { return is_sun_in_forbidden_angle; } - inline bool GetIsEarthInForbiddenAngle() const { return is_earth_in_forbidden_angle; } - inline bool GetIsMoonInForbiddenAngle() const { return is_moon_in_forbidden_angle; } - - protected: - private: - libra::Quaternion q_b2c_; //!< Quaternion from the body frame to component frame - libra::Vector<3> sight_; //!< Sight direction vector in the component frame - - double sun_forbidden_angle_; //!< Sun forbidden angle [rad] - double earth_forbidden_angle_; //!< Earth forbidden angle [rad] - double moon_forbidden_angle_; //!< Moon forbidden angle [rad] - - int x_num_of_pix_; //!< Number of pixel on X-axis in the image plane - int y_num_of_pix_; //!< Number of pixel on Y-axis in the image plane - double x_fov_par_pix_; //!< Field of view per pixel of X-axis in the image plane [rad/pix] - double y_fov_par_pix_; //!< Field of view per pixel of Y-axis in the image plane [rad/pix] - double x_field_of_view_rad; //!< Field of view of X-axis in the image plane [rad/pix] - double y_field_of_view_rad; //!< Field of view of Y-axis in the image plane [rad/pix] - - bool is_sun_in_forbidden_angle = false; //!< Is the sun in the forbidden angle - bool is_earth_in_forbidden_angle = false; //!< Is the earth in the forbidden angle - bool is_moon_in_forbidden_angle = false; //!< Is the moon in the forbidden angle - - size_t num_of_logged_stars_; //!< Number of logged stars - - libra::Vector<2> sun_pos_imgsensor{-1}; //!< Position of the sun on the image plane - libra::Vector<2> earth_pos_imgsensor{-1}; //!< Position of the earth on the image plane - libra::Vector<2> moon_pos_imgsensor{-1}; //!< Position of the moon on the image plane - - std::vector star_in_sight; //!< Star information in the field of view - - /** - * @fn JudgeForbiddenAngle - * @brief Judge the forbidden angles are violated - * @param [in] target_b: Direction vector of target on the body fixed frame - * @param [in] forbidden_angle: Forbidden angle [rad] - */ - bool JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle); - - // Override functions for ComponentBase - /** - * @fn MainRoutine - * @brief Main routine to calculate force generation - */ - void MainRoutine(int count); - - /** - * @fn Observe - * @brief Convert body fixed direction vector to position on image sensor plane - * @param [out] pos_imgsensor: Position on image sensor plane - * @param [in] target_b: Direction vector of target on the body fixed frame - */ - void Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b); - /** - * @fn ObserveStars - * @brief Observe stars from Hipparcos catalogue - */ - void ObserveStars(); - - const Attitude* attitude_; //!< Attitude information - const HipparcosCatalogue* hipp_; //!< Star information - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information - - // Override ILoggable - /** - * @fn GetLogHeader - * @brief Override GetLogHeader function of ILoggable - */ - virtual std::string GetLogHeader() const; - /** - * @fn GetLogValue - * @brief Override GetLogValue function of ILoggable - */ - virtual std::string GetLogValue() const; - - // For debug ********************************************** - // Vector<3> sun_pos_c; - // Vector<3> earth_pos_c; - // Vector<3> moon_pos_c; - // double angle_sun; - // double angle_earth; - // double angle_moon; - //************************************************************* -}; From 2ff0458ca1570239beadcea8dd5c291241f01025 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:05:41 +0100 Subject: [PATCH 0284/1086] Rename Mission/Telescope --- src/components/mission/InitTelescope.cpp | 54 ++++++ src/components/mission/InitTelescope.hpp | 20 +++ src/components/mission/Telescope.cpp | 202 +++++++++++++++++++++++ src/components/mission/Telescope.h | 123 ++++++++++++++ 4 files changed, 399 insertions(+) create mode 100644 src/components/mission/InitTelescope.cpp create mode 100644 src/components/mission/InitTelescope.hpp create mode 100644 src/components/mission/Telescope.cpp create mode 100644 src/components/mission/Telescope.h diff --git a/src/components/mission/InitTelescope.cpp b/src/components/mission/InitTelescope.cpp new file mode 100644 index 000000000..8e76caec1 --- /dev/null +++ b/src/components/mission/InitTelescope.cpp @@ -0,0 +1,54 @@ +/* + * @file InitTelescope.cpp + * @brief Initialize function of Telescope + */ + +#include "InitTelescope.hpp" + +#include + +#include + +#include "interface/initialize/initialize_file_access.hpp" + +using namespace std; + +Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, + const LocalCelestialInformation* local_celes_info) { + using libra::pi; + + IniAccess Telescope_conf(fname); + const string st_sensor_id = std::to_string(static_cast(sensor_id)); + const char* cs = st_sensor_id.data(); + + char TelescopeSection[30] = "TELESCOPE_"; +#ifdef WIN32 + strcat_s(TelescopeSection, cs); +#else + strcat(TelescopeSection, cs); +#endif + + Quaternion q_b2c; + Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", q_b2c); + + double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_exclusion_angle_deg"); + double sun_forbidden_angle_rad = sun_forbidden_angle_deg * pi / 180; // deg to rad + double earth_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "earth_exclusion_angle_deg"); + double earth_forbidden_angle_rad = earth_forbidden_angle_deg * pi / 180; // deg to rad + double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_exclusion_angle_deg"); + double moon_forbidden_angle_rad = moon_forbidden_angle_deg * pi / 180; // deg to rad + + int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); + int y_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_number_of_pixel"); + + double x_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_deg_per_pixel"); + double x_fov_par_pix_rad = x_fov_par_pix_deg * pi / 180; // deg to rad + double y_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_deg_per_pixel"); + double y_fov_par_pix_rad = y_fov_par_pix_deg * pi / 180; // deg to rad + + int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); + + Telescope telescope(clock_gen, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, y_num_of_pix, + x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); + return telescope; +} diff --git a/src/components/mission/InitTelescope.hpp b/src/components/mission/InitTelescope.hpp new file mode 100644 index 000000000..f2f578b7b --- /dev/null +++ b/src/components/mission/InitTelescope.hpp @@ -0,0 +1,20 @@ +/* + * @file InitTelescope.hpp + * @brief Initialize function of Telescope + */ +#pragma once + +#include + +/* + * @fn InitTelescope + * @brief Initialize function of Telescope + * @param [in] clock_gen: Clock generator + * @param [in] sensor_id: Sensor ID + * @param [in] fname: Path to initialize file + * @param [in] attitude: Attitude information + * @param [in] hipp: Star information by Hipparcos catalogue + * @param [in] local_celes_info: Local celestial information + */ +Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, + const LocalCelestialInformation* local_celes_info); diff --git a/src/components/mission/Telescope.cpp b/src/components/mission/Telescope.cpp new file mode 100644 index 000000000..c100cd68d --- /dev/null +++ b/src/components/mission/Telescope.cpp @@ -0,0 +1,202 @@ +/* + * @file Telescope.cpp + * @brief Component emulation: Telescope + */ + +#include "Telescope.h" + +#include +#include + +using namespace std; +using namespace libra; + +Telescope::Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, + double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, + size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, + const LocalCelestialInformation* local_celes_info) + : ComponentBase(1, clock_gen), + q_b2c_(q_b2c), + sun_forbidden_angle_(sun_forbidden_angle), + earth_forbidden_angle_(earth_forbidden_angle), + moon_forbidden_angle_(moon_forbidden_angle), + x_num_of_pix_(x_num_of_pix), + y_num_of_pix_(y_num_of_pix), + x_fov_par_pix_(x_fov_par_pix), + y_fov_par_pix_(y_fov_par_pix), + num_of_logged_stars_(num_of_logged_stars), + attitude_(attitude), + hipp_(hipp), + local_celes_info_(local_celes_info) { + is_sun_in_forbidden_angle = true; + is_earth_in_forbidden_angle = true; + is_moon_in_forbidden_angle = true; + + x_field_of_view_rad = x_num_of_pix_ * x_fov_par_pix_; + y_field_of_view_rad = y_num_of_pix_ * y_fov_par_pix_; + assert(x_field_of_view_rad < libra::pi_2); // Avoid the case that the field of view is over 90 degrees + assert(y_field_of_view_rad < libra::pi_2); + + sight_ = Vector<3>(0); + sight_[0] = 1; // (1,0,0) at component frame, Sight direction vector + + // Set 0 when t=0 + for (size_t i = 0; i < num_of_logged_stars_; i++) { + Star star; + star.hipdata.hip_num = -1; + star.hipdata.vmag = -1; + star.hipdata.ra = -1; + star.hipdata.de = -1; + star.pos_imgsensor[0] = -1; + star.pos_imgsensor[1] = -1; + + star_in_sight.push_back(star); + } +} + +Telescope::~Telescope() {} + +void Telescope::MainRoutine(int count) { + UNUSED(count); + // Check forbidden angle + is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("SUN"), sun_forbidden_angle_); + is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("EARTH"), earth_forbidden_angle_); + is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("MOON"), moon_forbidden_angle_); + // Position calculation of celestial bodies from CelesInfo + Observe(sun_pos_imgsensor, local_celes_info_->GetPosFromSC_b("SUN")); + Observe(earth_pos_imgsensor, local_celes_info_->GetPosFromSC_b("EARTH")); + Observe(moon_pos_imgsensor, local_celes_info_->GetPosFromSC_b("MOON")); + // Position calculation of stars from Hipparcos Catalogue + // No update when Hipparocos Catalogue was not readed + if (hipp_->IsCalcEnabled) ObserveStars(); + // Debug ****************************************************************** + // sun_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("SUN")); + // earth_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("EARTH")); + // moon_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("MOON")); + // angle_sun = angle(sight_, sun_pos_c) * 180/libra::pi; + // angle_earth = angle(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = angle(sight_, moon_pos_c) * 180 / libra::pi; + //****************************************************************************** +} + +bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { + Quaternion q_c2b = q_b2c_.conjugate(); + Vector<3> sight_b = q_c2b.frame_conv(sight_); + double angle_rad = libra::angle(target_b, sight_b); + if (angle_rad < forbidden_angle) { + return true; + } else + return false; +} + +void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b) { + Vector<3, double> target_c = q_b2c_.frame_conv(target_b); + double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame + double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame + + if (abs(arg_x) < x_field_of_view_rad && abs(arg_y) < y_field_of_view_rad) { + pos_imgsensor[0] = x_num_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2; + pos_imgsensor[1] = y_num_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2; + } else { // Return -1 when the body is in the out of FoV + pos_imgsensor[0] = -1; + pos_imgsensor[1] = -1; + } +} + +void Telescope::ObserveStars() { + Quaternion q_i2b = attitude_->GetQuaternion_i2b(); + + star_in_sight.clear(); // Clear first + int count = 0; // Counter for while loop + + while (star_in_sight.size() < num_of_logged_stars_) { + Vector<3> target_b = hipp_->GetStarDir_b(count, q_i2b); + Vector<3> target_c = q_b2c_.frame_conv(target_b); + + double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame + double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame + + if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { + Star star; + star.hipdata.hip_num = hipp_->GetHipID(count); + star.hipdata.vmag = hipp_->GetVmag(count); + star.hipdata.ra = hipp_->GetRA(count); + star.hipdata.de = hipp_->GetDE(count); + star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; + star.pos_imgsensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; + + star_in_sight.push_back(star); + } + + count++; + + // If read all catalogue, fill -1 and break the loop + if (count >= hipp_->GetCatalogueSize()) { + while (star_in_sight.size() < num_of_logged_stars_) { + Star star; + star.hipdata.hip_num = -1; + star.hipdata.vmag = -1; + star.hipdata.ra = -1; + star.hipdata.de = -1; + star.pos_imgsensor[0] = -1; + star.pos_imgsensor[1] = -1; + + star_in_sight.push_back(star); + } + + break; + } + } +} + +string Telescope::GetLogHeader() const { + string str_tmp = ""; + + std::string component_name = "telescope_"; + + str_tmp += WriteScalar(component_name + "sun_in_exclusion_angle", ""); + str_tmp += WriteScalar(component_name + "earth_in_exclusion_angle", ""); + str_tmp += WriteScalar(component_name + "moon_in_exclusion_angle", ""); + str_tmp += WriteVector(component_name + "sun_position", "img", "pix", 2); + str_tmp += WriteVector(component_name + "earth_position", "img", "pix", 2); + str_tmp += WriteVector(component_name + "moon_position", "img", "pix", 2); + // When Hipparcos Catalogue was not read, no output of ObserveStars + if (hipp_->IsCalcEnabled) { + for (size_t i = 0; i < num_of_logged_stars_; i++) { + str_tmp += WriteScalar(component_name + "hipparcos_id (" + to_string(i) + ")", " "); + str_tmp += WriteScalar(component_name + "visible_magnitude (" + to_string(i) + ")", " "); + str_tmp += WriteVector(component_name + "star_position (" + to_string(i) + ")", "img", "pix", 2); + } + } + + // Debug output ********************************************** + // str_tmp += WriteScalar("angle_sun", ""); + // str_tmp += WriteScalar("angle_earth", ""); + // str_tmp += WriteScalar("angle_moon", ""); + //********************************************************** + return str_tmp; +} + +string Telescope::GetLogValue() const { + string str_tmp = ""; + str_tmp += WriteScalar(is_sun_in_forbidden_angle); + str_tmp += WriteScalar(is_earth_in_forbidden_angle); + str_tmp += WriteScalar(is_moon_in_forbidden_angle); + str_tmp += WriteVector(sun_pos_imgsensor); + str_tmp += WriteVector(earth_pos_imgsensor); + str_tmp += WriteVector(moon_pos_imgsensor); + // When Hipparcos Catalogue was not read, no output of ObserveStars + if (hipp_->IsCalcEnabled) { + for (size_t i = 0; i < num_of_logged_stars_; i++) { + str_tmp += WriteScalar(star_in_sight[i].hipdata.hip_num); + str_tmp += WriteScalar(star_in_sight[i].hipdata.vmag); + str_tmp += WriteVector(star_in_sight[i].pos_imgsensor); + } + } + + // Debug output ********************************************** + // str_tmp += WriteScalar(angle_sun); + // str_tmp += WriteScalar(angle_earth); + // str_tmp += WriteScalar(angle_moon); + //********************************************************** + return str_tmp; +} diff --git a/src/components/mission/Telescope.h b/src/components/mission/Telescope.h new file mode 100644 index 000000000..83640524e --- /dev/null +++ b/src/components/mission/Telescope.h @@ -0,0 +1,123 @@ +/* + * @file Telescope.h + * @brief Component emulation: Telescope + */ + +#pragma once +#include +#include + +#include +#include +#include +#include +#include +#include + +/* + * @struct Star + * @brief Information of stars in the telescope's field of view + */ +struct Star { + HipData hipdata; //!< Hipparcos data + libra::Vector<2> pos_imgsensor; //!< Position of image sensor +}; + +/* + * @class Telescope + * @brief Component emulation: Telescope + */ +class Telescope : public ComponentBase, public ILoggable { + public: + Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, + double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, + const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); + + ~Telescope(); + + // Getter + inline bool GetIsSunInForbiddenAngle() const { return is_sun_in_forbidden_angle; } + inline bool GetIsEarthInForbiddenAngle() const { return is_earth_in_forbidden_angle; } + inline bool GetIsMoonInForbiddenAngle() const { return is_moon_in_forbidden_angle; } + + protected: + private: + libra::Quaternion q_b2c_; //!< Quaternion from the body frame to component frame + libra::Vector<3> sight_; //!< Sight direction vector in the component frame + + double sun_forbidden_angle_; //!< Sun forbidden angle [rad] + double earth_forbidden_angle_; //!< Earth forbidden angle [rad] + double moon_forbidden_angle_; //!< Moon forbidden angle [rad] + + int x_num_of_pix_; //!< Number of pixel on X-axis in the image plane + int y_num_of_pix_; //!< Number of pixel on Y-axis in the image plane + double x_fov_par_pix_; //!< Field of view per pixel of X-axis in the image plane [rad/pix] + double y_fov_par_pix_; //!< Field of view per pixel of Y-axis in the image plane [rad/pix] + double x_field_of_view_rad; //!< Field of view of X-axis in the image plane [rad/pix] + double y_field_of_view_rad; //!< Field of view of Y-axis in the image plane [rad/pix] + + bool is_sun_in_forbidden_angle = false; //!< Is the sun in the forbidden angle + bool is_earth_in_forbidden_angle = false; //!< Is the earth in the forbidden angle + bool is_moon_in_forbidden_angle = false; //!< Is the moon in the forbidden angle + + size_t num_of_logged_stars_; //!< Number of logged stars + + libra::Vector<2> sun_pos_imgsensor{-1}; //!< Position of the sun on the image plane + libra::Vector<2> earth_pos_imgsensor{-1}; //!< Position of the earth on the image plane + libra::Vector<2> moon_pos_imgsensor{-1}; //!< Position of the moon on the image plane + + std::vector star_in_sight; //!< Star information in the field of view + + /** + * @fn JudgeForbiddenAngle + * @brief Judge the forbidden angles are violated + * @param [in] target_b: Direction vector of target on the body fixed frame + * @param [in] forbidden_angle: Forbidden angle [rad] + */ + bool JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle); + + // Override functions for ComponentBase + /** + * @fn MainRoutine + * @brief Main routine to calculate force generation + */ + void MainRoutine(int count); + + /** + * @fn Observe + * @brief Convert body fixed direction vector to position on image sensor plane + * @param [out] pos_imgsensor: Position on image sensor plane + * @param [in] target_b: Direction vector of target on the body fixed frame + */ + void Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b); + /** + * @fn ObserveStars + * @brief Observe stars from Hipparcos catalogue + */ + void ObserveStars(); + + const Attitude* attitude_; //!< Attitude information + const HipparcosCatalogue* hipp_; //!< Star information + const LocalCelestialInformation* local_celes_info_; //!< Local celestial information + + // Override ILoggable + /** + * @fn GetLogHeader + * @brief Override GetLogHeader function of ILoggable + */ + virtual std::string GetLogHeader() const; + /** + * @fn GetLogValue + * @brief Override GetLogValue function of ILoggable + */ + virtual std::string GetLogValue() const; + + // For debug ********************************************** + // Vector<3> sun_pos_c; + // Vector<3> earth_pos_c; + // Vector<3> moon_pos_c; + // double angle_sun; + // double angle_earth; + // double angle_moon; + //************************************************************* +}; From 20030fd4a1dec9826501c0aa06b92f4c555e73c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:06:28 +0100 Subject: [PATCH 0285/1086] Rename Thermal --- src/components/{Thermal => thermal}/.gitkeep | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename src/components/{Thermal => thermal}/.gitkeep (100%) diff --git a/src/components/Thermal/.gitkeep b/src/components/thermal/.gitkeep similarity index 100% rename from src/components/Thermal/.gitkeep rename to src/components/thermal/.gitkeep From 3904ad987606b960fb2fab4bb0629e787ff7bd23 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:08:49 +0100 Subject: [PATCH 0286/1086] Rename Power --- src/components/CMakeLists.txt | 16 ++++++++-------- src/components/{Power => power}/BAT.cpp | 0 src/components/{Power => power}/BAT.h | 0 .../{Power => power}/CsvScenarioInterface.cpp | 0 .../{Power => power}/CsvScenarioInterface.h | 0 src/components/{Power => power}/InitBat.cpp | 0 src/components/{Power => power}/InitBat.hpp | 2 +- .../{Power => power}/InitPcu_InitialStudy.cpp | 0 .../{Power => power}/InitPcu_InitialStudy.hpp | 2 +- src/components/{Power => power}/InitSap.cpp | 0 src/components/{Power => power}/InitSap.hpp | 2 +- src/components/{Power => power}/PCU.cpp | 0 src/components/{Power => power}/PCU.h | 0 .../{Power => power}/PCU_InitialStudy.cpp | 2 +- .../{Power => power}/PCU_InitialStudy.h | 0 src/components/{Power => power}/SAP.cpp | 2 +- src/components/{Power => power}/SAP.h | 0 .../sample_spacecraft/sample_components.hpp | 2 +- 18 files changed, 14 insertions(+), 14 deletions(-) rename src/components/{Power => power}/BAT.cpp (100%) rename src/components/{Power => power}/BAT.h (100%) rename src/components/{Power => power}/CsvScenarioInterface.cpp (100%) rename src/components/{Power => power}/CsvScenarioInterface.h (100%) rename src/components/{Power => power}/InitBat.cpp (100%) rename src/components/{Power => power}/InitBat.hpp (92%) rename src/components/{Power => power}/InitPcu_InitialStudy.cpp (100%) rename src/components/{Power => power}/InitPcu_InitialStudy.hpp (93%) rename src/components/{Power => power}/InitSap.cpp (100%) rename src/components/{Power => power}/InitSap.hpp (96%) rename src/components/{Power => power}/PCU.cpp (100%) rename src/components/{Power => power}/PCU.h (100%) rename src/components/{Power => power}/PCU_InitialStudy.cpp (98%) rename src/components/{Power => power}/PCU_InitialStudy.h (100%) rename src/components/{Power => power}/SAP.cpp (98%) rename src/components/{Power => power}/SAP.h (100%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index b86e787b6..2188e65e0 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -48,14 +48,14 @@ add_library(${PROJECT_NAME} STATIC mission/Telescope.cpp mission/InitTelescope.cpp - Power/PCU.cpp - Power/BAT.cpp - Power/InitBat.cpp - Power/PCU_InitialStudy.cpp - Power/InitPcu_InitialStudy.cpp - Power/SAP.cpp - Power/InitSap.cpp - Power/CsvScenarioInterface.cpp + power/PCU.cpp + power/BAT.cpp + power/InitBat.cpp + power/PCU_InitialStudy.cpp + power/InitPcu_InitialStudy.cpp + power/SAP.cpp + power/InitSap.cpp + power/CsvScenarioInterface.cpp Propulsion/SimpleThruster.cpp Propulsion/InitSimpleThruster.cpp diff --git a/src/components/Power/BAT.cpp b/src/components/power/BAT.cpp similarity index 100% rename from src/components/Power/BAT.cpp rename to src/components/power/BAT.cpp diff --git a/src/components/Power/BAT.h b/src/components/power/BAT.h similarity index 100% rename from src/components/Power/BAT.h rename to src/components/power/BAT.h diff --git a/src/components/Power/CsvScenarioInterface.cpp b/src/components/power/CsvScenarioInterface.cpp similarity index 100% rename from src/components/Power/CsvScenarioInterface.cpp rename to src/components/power/CsvScenarioInterface.cpp diff --git a/src/components/Power/CsvScenarioInterface.h b/src/components/power/CsvScenarioInterface.h similarity index 100% rename from src/components/Power/CsvScenarioInterface.h rename to src/components/power/CsvScenarioInterface.h diff --git a/src/components/Power/InitBat.cpp b/src/components/power/InitBat.cpp similarity index 100% rename from src/components/Power/InitBat.cpp rename to src/components/power/InitBat.cpp diff --git a/src/components/Power/InitBat.hpp b/src/components/power/InitBat.hpp similarity index 92% rename from src/components/Power/InitBat.hpp rename to src/components/power/InitBat.hpp index 2ab188883..fddf1ce9d 100644 --- a/src/components/Power/InitBat.hpp +++ b/src/components/power/InitBat.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitBAT diff --git a/src/components/Power/InitPcu_InitialStudy.cpp b/src/components/power/InitPcu_InitialStudy.cpp similarity index 100% rename from src/components/Power/InitPcu_InitialStudy.cpp rename to src/components/power/InitPcu_InitialStudy.cpp diff --git a/src/components/Power/InitPcu_InitialStudy.hpp b/src/components/power/InitPcu_InitialStudy.hpp similarity index 93% rename from src/components/Power/InitPcu_InitialStudy.hpp rename to src/components/power/InitPcu_InitialStudy.hpp index 1974e18fa..b0d55d483 100644 --- a/src/components/Power/InitPcu_InitialStudy.hpp +++ b/src/components/power/InitPcu_InitialStudy.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitPCU_InitialStudy diff --git a/src/components/Power/InitSap.cpp b/src/components/power/InitSap.cpp similarity index 100% rename from src/components/Power/InitSap.cpp rename to src/components/power/InitSap.cpp diff --git a/src/components/Power/InitSap.hpp b/src/components/power/InitSap.hpp similarity index 96% rename from src/components/Power/InitSap.hpp rename to src/components/power/InitSap.hpp index ff40f4ae1..117f26937 100644 --- a/src/components/Power/InitSap.hpp +++ b/src/components/power/InitSap.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitSAP diff --git a/src/components/Power/PCU.cpp b/src/components/power/PCU.cpp similarity index 100% rename from src/components/Power/PCU.cpp rename to src/components/power/PCU.cpp diff --git a/src/components/Power/PCU.h b/src/components/power/PCU.h similarity index 100% rename from src/components/Power/PCU.h rename to src/components/power/PCU.h diff --git a/src/components/Power/PCU_InitialStudy.cpp b/src/components/power/PCU_InitialStudy.cpp similarity index 98% rename from src/components/Power/PCU_InitialStudy.cpp rename to src/components/power/PCU_InitialStudy.cpp index ddb68f9be..b3ed28009 100644 --- a/src/components/Power/PCU_InitialStudy.cpp +++ b/src/components/power/PCU_InitialStudy.cpp @@ -5,7 +5,7 @@ #include "PCU_InitialStudy.h" -#include +#include #include #include diff --git a/src/components/Power/PCU_InitialStudy.h b/src/components/power/PCU_InitialStudy.h similarity index 100% rename from src/components/Power/PCU_InitialStudy.h rename to src/components/power/PCU_InitialStudy.h diff --git a/src/components/Power/SAP.cpp b/src/components/power/SAP.cpp similarity index 98% rename from src/components/Power/SAP.cpp rename to src/components/power/SAP.cpp index 714f89866..fe98019c9 100644 --- a/src/components/Power/SAP.cpp +++ b/src/components/power/SAP.cpp @@ -1,6 +1,6 @@ #include "SAP.h" -#include +#include #include diff --git a/src/components/Power/SAP.h b/src/components/power/SAP.h similarity index 100% rename from src/components/Power/SAP.h rename to src/components/power/SAP.h diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index f604f589e..401168906 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #include -#include +#include #include #include From a69904578bc7703c4717b25375b47c10ae9247dd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:09:39 +0100 Subject: [PATCH 0287/1086] Rename Propulsion --- src/components/CMakeLists.txt | 4 ++-- .../{Propulsion => propulsion}/InitSimpleThruster.cpp | 0 .../{Propulsion => propulsion}/InitSimpleThruster.hpp | 2 +- src/components/{Propulsion => propulsion}/SimpleThruster.cpp | 0 src/components/{Propulsion => propulsion}/SimpleThruster.h | 0 .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 6 files changed, 4 insertions(+), 4 deletions(-) rename src/components/{Propulsion => propulsion}/InitSimpleThruster.cpp (100%) rename src/components/{Propulsion => propulsion}/InitSimpleThruster.hpp (95%) rename src/components/{Propulsion => propulsion}/SimpleThruster.cpp (100%) rename src/components/{Propulsion => propulsion}/SimpleThruster.h (100%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 2188e65e0..1fc1933fc 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -57,8 +57,8 @@ add_library(${PROJECT_NAME} STATIC power/InitSap.cpp power/CsvScenarioInterface.cpp - Propulsion/SimpleThruster.cpp - Propulsion/InitSimpleThruster.cpp + propulsion/SimpleThruster.cpp + propulsion/InitSimpleThruster.cpp ) diff --git a/src/components/Propulsion/InitSimpleThruster.cpp b/src/components/propulsion/InitSimpleThruster.cpp similarity index 100% rename from src/components/Propulsion/InitSimpleThruster.cpp rename to src/components/propulsion/InitSimpleThruster.cpp diff --git a/src/components/Propulsion/InitSimpleThruster.hpp b/src/components/propulsion/InitSimpleThruster.hpp similarity index 95% rename from src/components/Propulsion/InitSimpleThruster.hpp rename to src/components/propulsion/InitSimpleThruster.hpp index 55bf3154e..4f47610f9 100644 --- a/src/components/Propulsion/InitSimpleThruster.hpp +++ b/src/components/propulsion/InitSimpleThruster.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitSimpleThruster diff --git a/src/components/Propulsion/SimpleThruster.cpp b/src/components/propulsion/SimpleThruster.cpp similarity index 100% rename from src/components/Propulsion/SimpleThruster.cpp rename to src/components/propulsion/SimpleThruster.cpp diff --git a/src/components/Propulsion/SimpleThruster.h b/src/components/propulsion/SimpleThruster.h similarity index 100% rename from src/components/Propulsion/SimpleThruster.h rename to src/components/propulsion/SimpleThruster.h diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 401168906..99b207190 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include #include #include From 1c9be19417f37c6ff2df039f387b7db68e54ce05 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:12:41 +0100 Subject: [PATCH 0288/1086] Rename GNSSReceiver --- src/components/CMakeLists.txt | 2 +- src/components/aocs/InitGnssReceiver.hpp | 2 +- .../aocs/{GNSSReceiver.cpp => gnss_receiver.cpp} | 4 ++-- src/components/aocs/{GNSSReceiver.h => gnss_receiver.hpp} | 7 +++++-- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/components/aocs/{GNSSReceiver.cpp => gnss_receiver.cpp} (99%) rename src/components/aocs/{GNSSReceiver.h => gnss_receiver.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 1fc1933fc..695c22fae 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -22,7 +22,7 @@ add_library(${PROJECT_NAME} STATIC aocs/InitStt.cpp aocs/SunSensor.cpp aocs/InitSunSensor.cpp - aocs/GNSSReceiver.cpp + aocs/gnss_receiver.cpp aocs/InitGnssReceiver.cpp cdh/OBC.cpp diff --git a/src/components/aocs/InitGnssReceiver.hpp b/src/components/aocs/InitGnssReceiver.hpp index c339d5dce..ece18b45a 100644 --- a/src/components/aocs/InitGnssReceiver.hpp +++ b/src/components/aocs/InitGnssReceiver.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGNSSReceiver diff --git a/src/components/aocs/GNSSReceiver.cpp b/src/components/aocs/gnss_receiver.cpp similarity index 99% rename from src/components/aocs/GNSSReceiver.cpp rename to src/components/aocs/gnss_receiver.cpp index d2774dd65..0977156ce 100644 --- a/src/components/aocs/GNSSReceiver.cpp +++ b/src/components/aocs/gnss_receiver.cpp @@ -1,9 +1,9 @@ /** - * @file GNSSReceiver.cpp + * @file gnss_receiver.cpp * @brief Class to emulate GNSS receiver */ -#include "GNSSReceiver.h" +#include "gnss_receiver.hpp" #include diff --git a/src/components/aocs/GNSSReceiver.h b/src/components/aocs/gnss_receiver.hpp similarity index 98% rename from src/components/aocs/GNSSReceiver.h rename to src/components/aocs/gnss_receiver.hpp index 3a5120ef8..84495e7fe 100644 --- a/src/components/aocs/GNSSReceiver.h +++ b/src/components/aocs/gnss_receiver.hpp @@ -1,9 +1,10 @@ /** - * @file GNSSReceiver.h + * @file gnss_receiver.hpp * @brief Class to emulate GNSS receiver */ -#pragma once +#ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ +#define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ #include #include @@ -212,3 +213,5 @@ class GNSSReceiver : public ComponentBase, public ILoggable { */ void ConvertJulianDayToGPSTime(const double JulianDay); }; + +#endif // S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ From 2c5661131187c52225e255fc23e16fa0a02cb1df Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:14:17 +0100 Subject: [PATCH 0289/1086] Rename Gyro --- src/components/CMakeLists.txt | 2 +- src/components/aocs/InitGyro.hpp | 2 +- src/components/aocs/{Gyro.cpp => gyro_sensor.cpp} | 4 ++-- src/components/aocs/{Gyro.h => gyro_sensor.hpp} | 8 ++++---- 4 files changed, 8 insertions(+), 8 deletions(-) rename src/components/aocs/{Gyro.cpp => gyro_sensor.cpp} (96%) rename src/components/aocs/{Gyro.h => gyro_sensor.hpp} (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 695c22fae..f68619e31 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -8,7 +8,7 @@ add_library(${PROJECT_NAME} STATIC base_classes/ObcI2cTargetCommunicationBase.cpp base_classes/ObcGpioBase.cpp - aocs/Gyro.cpp + aocs/gyro_sensor.cpp aocs/InitGyro.cpp aocs/MagSensor.cpp aocs/InitMagSensor.cpp diff --git a/src/components/aocs/InitGyro.hpp b/src/components/aocs/InitGyro.hpp index c5407152c..2a99ef5cb 100644 --- a/src/components/aocs/InitGyro.hpp +++ b/src/components/aocs/InitGyro.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /** * @fn InitGyro diff --git a/src/components/aocs/Gyro.cpp b/src/components/aocs/gyro_sensor.cpp similarity index 96% rename from src/components/aocs/Gyro.cpp rename to src/components/aocs/gyro_sensor.cpp index 15fc19a8d..9741cb2a7 100644 --- a/src/components/aocs/Gyro.cpp +++ b/src/components/aocs/gyro_sensor.cpp @@ -1,9 +1,9 @@ /** - * @file Gyro.cpp + * @file gyro_sensor.cpp * @brief Class to emulate gyro sensor (angular velocity sensor) */ -#include "Gyro.h" +#include "gyro_sensor.hpp" #include "../cdh/OBC_C2A.h" diff --git a/src/components/aocs/Gyro.h b/src/components/aocs/gyro_sensor.hpp similarity index 94% rename from src/components/aocs/Gyro.h rename to src/components/aocs/gyro_sensor.hpp index 3cd881c1a..c0f14777d 100644 --- a/src/components/aocs/Gyro.h +++ b/src/components/aocs/gyro_sensor.hpp @@ -1,10 +1,10 @@ /** - * @file Gyro.h + * @file gyro_sensor.hpp * @brief Class to emulate gyro sensor (angular velocity sensor) */ -#ifndef Gyro_H_ -#define Gyro_H_ +#ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ #include #include @@ -85,4 +85,4 @@ class Gyro : public ComponentBase, public SensorBase, public ILoggable const Dynamics* dynamics_; //!< Dynamics information }; -#endif +#endif // S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ From 715df29593b613553e82f6645d8415678219c521 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:17:04 +0100 Subject: [PATCH 0290/1086] Rename InitGnssReceiver --- src/components/CMakeLists.txt | 2 +- ...{InitGnssReceiver.cpp => initialize_gnss_receiver.cpp} | 4 ++-- ...{InitGnssReceiver.hpp => initialize_gnss_receiver.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitGnssReceiver.cpp => initialize_gnss_receiver.cpp} (97%) rename src/components/aocs/{InitGnssReceiver.hpp => initialize_gnss_receiver.hpp} (86%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f68619e31..3933b6c1d 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -23,7 +23,7 @@ add_library(${PROJECT_NAME} STATIC aocs/SunSensor.cpp aocs/InitSunSensor.cpp aocs/gnss_receiver.cpp - aocs/InitGnssReceiver.cpp + aocs/initialize_gnss_receiver.cpp cdh/OBC.cpp cdh/OBC_C2A.cpp diff --git a/src/components/aocs/InitGnssReceiver.cpp b/src/components/aocs/initialize_gnss_receiver.cpp similarity index 97% rename from src/components/aocs/InitGnssReceiver.cpp rename to src/components/aocs/initialize_gnss_receiver.cpp index a115c9552..741cf769c 100644 --- a/src/components/aocs/InitGnssReceiver.cpp +++ b/src/components/aocs/initialize_gnss_receiver.cpp @@ -1,8 +1,8 @@ /** - * @file InitGnssReceiver.cpp + * @file initialize_gnss_receiver.cpp * @brief Initialize functions for GNSS Receiver */ -#include "InitGnssReceiver.hpp" +#include "initialize_gnss_receiver.hpp" #include diff --git a/src/components/aocs/InitGnssReceiver.hpp b/src/components/aocs/initialize_gnss_receiver.hpp similarity index 86% rename from src/components/aocs/InitGnssReceiver.hpp rename to src/components/aocs/initialize_gnss_receiver.hpp index ece18b45a..a18b9ac57 100644 --- a/src/components/aocs/InitGnssReceiver.hpp +++ b/src/components/aocs/initialize_gnss_receiver.hpp @@ -1,8 +1,10 @@ /** - * @file InitGnssReceiver.hpp + * @file initialize_gnss_receiver.hpp * @brief Initialize functions for GNSS Receiver */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ #include @@ -31,3 +33,5 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri */ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 99b207190..19e515873 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -14,7 +14,7 @@ #include #include #include -#include +#include #include #include #include From 2350d41459d13f649edca8497aabf99e72b705cc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:18:48 +0100 Subject: [PATCH 0291/1086] Rename InitGyro --- src/components/CMakeLists.txt | 2 +- .../aocs/{InitGyro.cpp => initialize_gyro_sensor.cpp} | 4 ++-- .../aocs/{InitGyro.hpp => initialize_gyro_sensor.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitGyro.cpp => initialize_gyro_sensor.cpp} (96%) rename src/components/aocs/{InitGyro.hpp => initialize_gyro_sensor.hpp} (84%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 3933b6c1d..cce794647 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -9,7 +9,7 @@ add_library(${PROJECT_NAME} STATIC base_classes/ObcGpioBase.cpp aocs/gyro_sensor.cpp - aocs/InitGyro.cpp + aocs/initialize_gyro_sensor.cpp aocs/MagSensor.cpp aocs/InitMagSensor.cpp aocs/MagTorquer.cpp diff --git a/src/components/aocs/InitGyro.cpp b/src/components/aocs/initialize_gyro_sensor.cpp similarity index 96% rename from src/components/aocs/InitGyro.cpp rename to src/components/aocs/initialize_gyro_sensor.cpp index e52504c68..12795ac47 100644 --- a/src/components/aocs/InitGyro.cpp +++ b/src/components/aocs/initialize_gyro_sensor.cpp @@ -1,8 +1,8 @@ /** - * @file InitGyro.cpp + * @file initialize_gyro_sensor.cpp * @brief Initialize functions for gyro sensor */ -#include "InitGyro.hpp" +#include "initialize_gyro_sensor.hpp" #include diff --git a/src/components/aocs/InitGyro.hpp b/src/components/aocs/initialize_gyro_sensor.hpp similarity index 84% rename from src/components/aocs/InitGyro.hpp rename to src/components/aocs/initialize_gyro_sensor.hpp index 2a99ef5cb..3aac32a8b 100644 --- a/src/components/aocs/InitGyro.hpp +++ b/src/components/aocs/initialize_gyro_sensor.hpp @@ -1,8 +1,10 @@ /** - * @file InitGyro.hpp + * @file initialize_gyro_sensor.hpp * @brief Initialize functions for gyro sensor */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ #include @@ -28,3 +30,5 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, */ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 19e515873..6e09abc79 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -15,7 +15,7 @@ #include #include #include -#include +#include #include #include #include From 3ad7cb2be833bcc8d57ca7b9e8942b758062a52e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:21:16 +0100 Subject: [PATCH 0292/1086] Rename InitMagSensor --- src/components/CMakeLists.txt | 2 +- .../{InitMagSensor.cpp => initialize_magnetometer.cpp} | 4 ++-- .../{InitMagSensor.hpp => initialize_magnetometer.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitMagSensor.cpp => initialize_magnetometer.cpp} (96%) rename src/components/aocs/{InitMagSensor.hpp => initialize_magnetometer.hpp} (84%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index cce794647..c082cf661 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -11,7 +11,7 @@ add_library(${PROJECT_NAME} STATIC aocs/gyro_sensor.cpp aocs/initialize_gyro_sensor.cpp aocs/MagSensor.cpp - aocs/InitMagSensor.cpp + aocs/initialize_magnetometer.cpp aocs/MagTorquer.cpp aocs/InitMagTorquer.cpp aocs/rw_ode.cpp diff --git a/src/components/aocs/InitMagSensor.cpp b/src/components/aocs/initialize_magnetometer.cpp similarity index 96% rename from src/components/aocs/InitMagSensor.cpp rename to src/components/aocs/initialize_magnetometer.cpp index c65346c68..eb7c0871e 100644 --- a/src/components/aocs/InitMagSensor.cpp +++ b/src/components/aocs/initialize_magnetometer.cpp @@ -1,8 +1,8 @@ /** - * @file InitMagSensor.cpp + * @file initialize_magnetometer.cpp * @brief Initialize functions for magnetometer */ -#include "InitMagSensor.hpp" +#include "initialize_magnetometer.hpp" #include "../base_classes/InitializeSensorBase.hpp" #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/InitMagSensor.hpp b/src/components/aocs/initialize_magnetometer.hpp similarity index 84% rename from src/components/aocs/InitMagSensor.hpp rename to src/components/aocs/initialize_magnetometer.hpp index f4a29dcc2..9b42520f0 100644 --- a/src/components/aocs/InitMagSensor.hpp +++ b/src/components/aocs/initialize_magnetometer.hpp @@ -1,8 +1,10 @@ /** - * @file InitMagSensor.hpp + * @file initialize_magnetometer.hpp * @brief Initialize functions for magnetometer */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ #include @@ -28,3 +30,5 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str */ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 6e09abc79..576710790 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -16,7 +16,7 @@ #include #include #include -#include +#include #include #include #include From 4270184c3583b95a41359437e37564a09ca08447 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:23:04 +0100 Subject: [PATCH 0293/1086] Rename InitMagTorquer --- src/components/CMakeLists.txt | 2 +- .../{InitMagTorquer.cpp => initialize_magnetorquer.cpp} | 4 ++-- .../{InitMagTorquer.hpp => initialize_magnetorquer.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitMagTorquer.cpp => initialize_magnetorquer.cpp} (98%) rename src/components/aocs/{InitMagTorquer.hpp => initialize_magnetorquer.hpp} (84%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index c082cf661..d340abce6 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -13,7 +13,7 @@ add_library(${PROJECT_NAME} STATIC aocs/MagSensor.cpp aocs/initialize_magnetometer.cpp aocs/MagTorquer.cpp - aocs/InitMagTorquer.cpp + aocs/initialize_magnetorquer.cpp aocs/rw_ode.cpp aocs/RWModel.cpp aocs/InitRwModel.cpp diff --git a/src/components/aocs/InitMagTorquer.cpp b/src/components/aocs/initialize_magnetorquer.cpp similarity index 98% rename from src/components/aocs/InitMagTorquer.cpp rename to src/components/aocs/initialize_magnetorquer.cpp index 621d68bf3..9da0a0196 100644 --- a/src/components/aocs/InitMagTorquer.cpp +++ b/src/components/aocs/initialize_magnetorquer.cpp @@ -1,8 +1,8 @@ /** - * @file InitMagTorquer.cpp + * @file initialize_magnetorquer.cpp * @brief Initialize functions for magnetorquer */ -#include "InitMagTorquer.hpp" +#include "initialize_magnetorquer.hpp" #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/InitMagTorquer.hpp b/src/components/aocs/initialize_magnetorquer.hpp similarity index 84% rename from src/components/aocs/InitMagTorquer.hpp rename to src/components/aocs/initialize_magnetorquer.hpp index e277fc0bf..24222874c 100644 --- a/src/components/aocs/InitMagTorquer.hpp +++ b/src/components/aocs/initialize_magnetorquer.hpp @@ -1,8 +1,10 @@ /** - * @file InitMagTorquer.hpp + * @file initialize_magnetorquer.hpp * @brief Initialize functions for magnetorquer */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ #include @@ -28,3 +30,5 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: */ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 576710790..cc3da8fc0 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include #include From 97fd3e3ab3475a8f54105b7ea035bebbcee99d80 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:29:07 +0100 Subject: [PATCH 0294/1086] Rename InitRwModel --- src/components/CMakeLists.txt | 2 +- .../{InitRwModel.cpp => initialize_reaction_wheel.cpp} | 4 ++-- .../{InitRwModel.hpp => initialize_reaction_wheel.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitRwModel.cpp => initialize_reaction_wheel.cpp} (98%) rename src/components/aocs/{InitRwModel.hpp => initialize_reaction_wheel.hpp} (84%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index d340abce6..119ca6d84 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -16,7 +16,7 @@ add_library(${PROJECT_NAME} STATIC aocs/initialize_magnetorquer.cpp aocs/rw_ode.cpp aocs/RWModel.cpp - aocs/InitRwModel.cpp + aocs/initialize_reaction_wheel.cpp aocs/RWJitter.cpp aocs/STT.cpp aocs/InitStt.cpp diff --git a/src/components/aocs/InitRwModel.cpp b/src/components/aocs/initialize_reaction_wheel.cpp similarity index 98% rename from src/components/aocs/InitRwModel.cpp rename to src/components/aocs/initialize_reaction_wheel.cpp index 6ffd72166..a706c2687 100644 --- a/src/components/aocs/InitRwModel.cpp +++ b/src/components/aocs/initialize_reaction_wheel.cpp @@ -1,8 +1,8 @@ /** - * @file InitRwModel.cpp + * @file initialize_reaction_wheel.cpp * @brief Initialize functions for Reaction Wheel */ -#include "InitRwModel.hpp" +#include "initialize_reaction_wheel.hpp" #include diff --git a/src/components/aocs/InitRwModel.hpp b/src/components/aocs/initialize_reaction_wheel.hpp similarity index 84% rename from src/components/aocs/InitRwModel.hpp rename to src/components/aocs/initialize_reaction_wheel.hpp index e3b14a677..8589b3064 100644 --- a/src/components/aocs/InitRwModel.hpp +++ b/src/components/aocs/initialize_reaction_wheel.hpp @@ -1,8 +1,10 @@ /** - * @file InitRwModel.hpp + * @file initialize_reaction_wheel.hpp * @brief Initialize functions for Reaction Wheel */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ #include @@ -28,3 +30,5 @@ RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file */ RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, double compo_update_step); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index cc3da8fc0..7e28a9f0a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include #include #include From 8aba8b482452c53a3053324fad0501f1ef802edf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:30:49 +0100 Subject: [PATCH 0295/1086] Rename InitStt --- src/components/CMakeLists.txt | 2 +- .../aocs/{InitStt.cpp => initialize_star_sensor.cpp} | 4 ++-- .../aocs/{InitStt.hpp => initialize_star_sensor.hpp} | 7 +++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/components/aocs/{InitStt.cpp => initialize_star_sensor.cpp} (98%) rename src/components/aocs/{InitStt.hpp => initialize_star_sensor.hpp} (86%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 119ca6d84..751892507 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -19,7 +19,7 @@ add_library(${PROJECT_NAME} STATIC aocs/initialize_reaction_wheel.cpp aocs/RWJitter.cpp aocs/STT.cpp - aocs/InitStt.cpp + aocs/initialize_star_sensor.cpp aocs/SunSensor.cpp aocs/InitSunSensor.cpp aocs/gnss_receiver.cpp diff --git a/src/components/aocs/InitStt.cpp b/src/components/aocs/initialize_star_sensor.cpp similarity index 98% rename from src/components/aocs/InitStt.cpp rename to src/components/aocs/initialize_star_sensor.cpp index 9fad8fbd6..a87b1734f 100644 --- a/src/components/aocs/InitStt.cpp +++ b/src/components/aocs/initialize_star_sensor.cpp @@ -1,8 +1,8 @@ /** - * @file InitStt.cpp + * @file initialize_star_sensor.cpp * @brief Initialize functions for star sensor */ -#include "InitStt.hpp" +#include "initialize_star_sensor.hpp" #include diff --git a/src/components/aocs/InitStt.hpp b/src/components/aocs/initialize_star_sensor.hpp similarity index 86% rename from src/components/aocs/InitStt.hpp rename to src/components/aocs/initialize_star_sensor.hpp index 705e96e84..7842d388c 100644 --- a/src/components/aocs/InitStt.hpp +++ b/src/components/aocs/initialize_star_sensor.hpp @@ -1,9 +1,10 @@ /** - * @file InitStt.hpp + * @file initialize_star_sensor.hpp * @brief Initialize functions for star sensor */ -#pragma once +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ #include @@ -32,3 +33,5 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const std::string fname, d */ STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 7e28a9f0a..124155e18 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include #include #include From 527e7b9fe524843b2cb89de0445a728ac40a50e4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:32:20 +0100 Subject: [PATCH 0296/1086] Rename InitSunSensor --- src/components/CMakeLists.txt | 2 +- .../aocs/{InitSunSensor.cpp => initialize_sun_sensor.cpp} | 4 ++-- .../aocs/{InitSunSensor.hpp => initialize_sun_sensor.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/aocs/{InitSunSensor.cpp => initialize_sun_sensor.cpp} (97%) rename src/components/aocs/{InitSunSensor.hpp => initialize_sun_sensor.hpp} (85%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 751892507..8633a8363 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -21,7 +21,7 @@ add_library(${PROJECT_NAME} STATIC aocs/STT.cpp aocs/initialize_star_sensor.cpp aocs/SunSensor.cpp - aocs/InitSunSensor.cpp + aocs/initialize_sun_sensor.cpp aocs/gnss_receiver.cpp aocs/initialize_gnss_receiver.cpp diff --git a/src/components/aocs/InitSunSensor.cpp b/src/components/aocs/initialize_sun_sensor.cpp similarity index 97% rename from src/components/aocs/InitSunSensor.cpp rename to src/components/aocs/initialize_sun_sensor.cpp index 229deaa51..fe486687d 100644 --- a/src/components/aocs/InitSunSensor.cpp +++ b/src/components/aocs/initialize_sun_sensor.cpp @@ -1,8 +1,8 @@ /** - * @file InitSunSensor.cpp + * @file initialize_sun_sensor.cpp * @brief Initialize functions for sun sensor */ -#include "InitSunSensor.hpp" +#include "initialize_sun_sensor.hpp" #include diff --git a/src/components/aocs/InitSunSensor.hpp b/src/components/aocs/initialize_sun_sensor.hpp similarity index 85% rename from src/components/aocs/InitSunSensor.hpp rename to src/components/aocs/initialize_sun_sensor.hpp index bda3602d3..41c7e87d5 100644 --- a/src/components/aocs/InitSunSensor.hpp +++ b/src/components/aocs/initialize_sun_sensor.hpp @@ -1,8 +1,10 @@ /** - * @file InitSunSensor.hpp + * @file initialize_sun_sensor.hpp * @brief Initialize functions for sun sensor */ -#pragma once + +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ #include @@ -29,3 +31,5 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::str */ SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info); + +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 124155e18..89030855d 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -20,7 +20,7 @@ #include #include #include -#include +#include #include #include #include From 3274aaec1176886a1abcd07f84b66369d4c26595 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:35:26 +0100 Subject: [PATCH 0297/1086] Rename MagSensor --- src/components/CMakeLists.txt | 2 +- src/components/aocs/initialize_magnetometer.hpp | 2 +- .../aocs/{MagSensor.cpp => magnetometer.cpp} | 4 ++-- src/components/aocs/{MagSensor.h => magnetometer.hpp} | 11 +++++------ 4 files changed, 9 insertions(+), 10 deletions(-) rename src/components/aocs/{MagSensor.cpp => magnetometer.cpp} (96%) rename src/components/aocs/{MagSensor.h => magnetometer.hpp} (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 8633a8363..bd7c25355 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -10,7 +10,7 @@ add_library(${PROJECT_NAME} STATIC aocs/gyro_sensor.cpp aocs/initialize_gyro_sensor.cpp - aocs/MagSensor.cpp + aocs/magnetometer.cpp aocs/initialize_magnetometer.cpp aocs/MagTorquer.cpp aocs/initialize_magnetorquer.cpp diff --git a/src/components/aocs/initialize_magnetometer.hpp b/src/components/aocs/initialize_magnetometer.hpp index 9b42520f0..196fb12ea 100644 --- a/src/components/aocs/initialize_magnetometer.hpp +++ b/src/components/aocs/initialize_magnetometer.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ #define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ -#include +#include /** * @fn InitMagSensor diff --git a/src/components/aocs/MagSensor.cpp b/src/components/aocs/magnetometer.cpp similarity index 96% rename from src/components/aocs/MagSensor.cpp rename to src/components/aocs/magnetometer.cpp index 2c887d481..cf8cbcfbb 100644 --- a/src/components/aocs/MagSensor.cpp +++ b/src/components/aocs/magnetometer.cpp @@ -1,8 +1,8 @@ /** - * @file MagSensor.cpp + * @file magnetometer.cpp * @brief Class to emulate magnetometer */ -#include "MagSensor.h" +#include "magnetometer.hpp" #include diff --git a/src/components/aocs/MagSensor.h b/src/components/aocs/magnetometer.hpp similarity index 94% rename from src/components/aocs/MagSensor.h rename to src/components/aocs/magnetometer.hpp index c4553da63..e5e3f5a96 100644 --- a/src/components/aocs/MagSensor.h +++ b/src/components/aocs/magnetometer.hpp @@ -1,15 +1,14 @@ /** - * @file MagSensor.h + * @file magnetometer.hpp * @brief Class to emulate magnetometer */ -#ifndef MagSensor_H_ -#define MagSensor_H_ - -#include +#ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ +#define S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ #include #include +#include #include "../base_classes/ComponentBase.h" #include "../base_classes/SensorBase.h" @@ -86,4 +85,4 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg const MagEnvironment* magnet_; //!< Geomagnetic environment }; -#endif +#endif // S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ From 817e6fcab57aaba6b9410877d7ae39b15d3278ac Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:37:15 +0100 Subject: [PATCH 0298/1086] Rename MagTorquer --- src/components/CMakeLists.txt | 2 +- src/components/aocs/initialize_magnetorquer.hpp | 2 +- .../aocs/{MagTorquer.cpp => magnetorquer.cpp} | 4 ++-- .../aocs/{MagTorquer.h => magnetorquer.hpp} | 11 +++++------ 4 files changed, 9 insertions(+), 10 deletions(-) rename src/components/aocs/{MagTorquer.cpp => magnetorquer.cpp} (98%) rename src/components/aocs/{MagTorquer.h => magnetorquer.hpp} (97%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index bd7c25355..843b2e9f4 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -12,7 +12,7 @@ add_library(${PROJECT_NAME} STATIC aocs/initialize_gyro_sensor.cpp aocs/magnetometer.cpp aocs/initialize_magnetometer.cpp - aocs/MagTorquer.cpp + aocs/magnetorquer.cpp aocs/initialize_magnetorquer.cpp aocs/rw_ode.cpp aocs/RWModel.cpp diff --git a/src/components/aocs/initialize_magnetorquer.hpp b/src/components/aocs/initialize_magnetorquer.hpp index 24222874c..ff232912f 100644 --- a/src/components/aocs/initialize_magnetorquer.hpp +++ b/src/components/aocs/initialize_magnetorquer.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ #define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ -#include +#include /** * @fn InitMagTorquer diff --git a/src/components/aocs/MagTorquer.cpp b/src/components/aocs/magnetorquer.cpp similarity index 98% rename from src/components/aocs/MagTorquer.cpp rename to src/components/aocs/magnetorquer.cpp index 65e9bb015..7c95f9147 100644 --- a/src/components/aocs/MagTorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -1,9 +1,9 @@ /** - * @file MagTorquer.cpp + * @file magnetorquer.cpp * @brief Class to emulate magnetorquer */ -#include "MagTorquer.h" +#include "magnetorquer.hpp" #include #include diff --git a/src/components/aocs/MagTorquer.h b/src/components/aocs/magnetorquer.hpp similarity index 97% rename from src/components/aocs/MagTorquer.h rename to src/components/aocs/magnetorquer.hpp index 8f5c19cf7..6f08c0c16 100644 --- a/src/components/aocs/MagTorquer.h +++ b/src/components/aocs/magnetorquer.hpp @@ -1,12 +1,10 @@ /** - * @file MagTorquer.h + * @file magnetorquer.hpp * @brief Class to emulate magnetorquer */ -#ifndef MTQ_H_ -#define MTQ_H_ - -#include +#ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ +#define S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ #include #include @@ -14,6 +12,7 @@ #include #include #include +#include #include "../base_classes/ComponentBase.h" @@ -135,4 +134,4 @@ class MagTorquer : public ComponentBase, public ILoggable { libra::Vector CalcOutputTorque(void); }; -#endif // MTQ_H_ +#endif // S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ From 23f40cab515b5cf85b546beaec0d725a1dac3f59 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:43:43 +0100 Subject: [PATCH 0299/1086] Rename rw_ode --- src/components/CMakeLists.txt | 2 +- src/components/aocs/RWModel.h | 2 +- .../aocs/{rw_ode.cpp => reaction_wheel_ode.cpp} | 4 ++-- .../aocs/{rw_ode.hpp => reaction_wheel_ode.hpp} | 10 ++++++---- 4 files changed, 10 insertions(+), 8 deletions(-) rename src/components/aocs/{rw_ode.cpp => reaction_wheel_ode.cpp} (96%) rename src/components/aocs/{rw_ode.hpp => reaction_wheel_ode.hpp} (92%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 843b2e9f4..c10a6c327 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -14,7 +14,7 @@ add_library(${PROJECT_NAME} STATIC aocs/initialize_magnetometer.cpp aocs/magnetorquer.cpp aocs/initialize_magnetorquer.cpp - aocs/rw_ode.cpp + aocs/reaction_wheel_ode.cpp aocs/RWModel.cpp aocs/initialize_reaction_wheel.cpp aocs/RWJitter.cpp diff --git a/src/components/aocs/RWModel.h b/src/components/aocs/RWModel.h index 5c7bfa3bf..a335d12aa 100644 --- a/src/components/aocs/RWModel.h +++ b/src/components/aocs/RWModel.h @@ -15,7 +15,7 @@ #include "../base_classes/ComponentBase.h" #include "RWJitter.h" -#include "rw_ode.hpp" +#include "reaction_wheel_ode.hpp" /* * @class RWModel diff --git a/src/components/aocs/rw_ode.cpp b/src/components/aocs/reaction_wheel_ode.cpp similarity index 96% rename from src/components/aocs/rw_ode.cpp rename to src/components/aocs/reaction_wheel_ode.cpp index fc54025ed..6ea13a6b1 100644 --- a/src/components/aocs/rw_ode.cpp +++ b/src/components/aocs/reaction_wheel_ode.cpp @@ -1,8 +1,8 @@ /* - * @file rw_ode.cpp + * @file reaction_wheel_ode.cpp * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -#include "rw_ode.hpp" +#include "reaction_wheel_ode.hpp" #include diff --git a/src/components/aocs/rw_ode.hpp b/src/components/aocs/reaction_wheel_ode.hpp similarity index 92% rename from src/components/aocs/rw_ode.hpp rename to src/components/aocs/reaction_wheel_ode.hpp index 32457f9c4..6492813cb 100644 --- a/src/components/aocs/rw_ode.hpp +++ b/src/components/aocs/reaction_wheel_ode.hpp @@ -1,9 +1,11 @@ /* - * @file rw_ode.hpp + * @file reaction_wheel_ode.hpp * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -#ifndef __RW_ODE_H__ -#define __RW_ODE_H__ + +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ + #include #include #include @@ -68,4 +70,4 @@ class RwOde : public libra::ODE<1> { double target_angular_velocity_; //!< Target angular velocity [rad/s] }; -#endif //__RW_ODE_H__ +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ From 39977b64a55d7f9c5b513dc24808d95775592a3a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:45:33 +0100 Subject: [PATCH 0300/1086] Rename RWJitter --- src/components/CMakeLists.txt | 2 +- src/components/aocs/RWModel.h | 2 +- .../aocs/{RWJitter.cpp => reaction_wheel_jitter.cpp} | 4 ++-- .../aocs/{RWJitter.h => reaction_wheel_jitter.hpp} | 7 ++++++- 4 files changed, 10 insertions(+), 5 deletions(-) rename src/components/aocs/{RWJitter.cpp => reaction_wheel_jitter.cpp} (98%) rename src/components/aocs/{RWJitter.h => reaction_wheel_jitter.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index c10a6c327..f435cca39 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -17,7 +17,7 @@ add_library(${PROJECT_NAME} STATIC aocs/reaction_wheel_ode.cpp aocs/RWModel.cpp aocs/initialize_reaction_wheel.cpp - aocs/RWJitter.cpp + aocs/reaction_wheel_jitter.cpp aocs/STT.cpp aocs/initialize_star_sensor.cpp aocs/SunSensor.cpp diff --git a/src/components/aocs/RWModel.h b/src/components/aocs/RWModel.h index a335d12aa..0d918173a 100644 --- a/src/components/aocs/RWModel.h +++ b/src/components/aocs/RWModel.h @@ -14,7 +14,7 @@ #include #include "../base_classes/ComponentBase.h" -#include "RWJitter.h" +#include "reaction_wheel_jitter.hpp" #include "reaction_wheel_ode.hpp" /* diff --git a/src/components/aocs/RWJitter.cpp b/src/components/aocs/reaction_wheel_jitter.cpp similarity index 98% rename from src/components/aocs/RWJitter.cpp rename to src/components/aocs/reaction_wheel_jitter.cpp index 23f835032..cfa5cd0dd 100644 --- a/src/components/aocs/RWJitter.cpp +++ b/src/components/aocs/reaction_wheel_jitter.cpp @@ -1,9 +1,9 @@ /* - * @file RWJitter.cpp + * @file reaction_wheel_jitter.cpp * @brief Class to calculate RW high-frequency jitter effect */ -#include "RWJitter.h" +#include "reaction_wheel_jitter.hpp" #include #include diff --git a/src/components/aocs/RWJitter.h b/src/components/aocs/reaction_wheel_jitter.hpp similarity index 96% rename from src/components/aocs/RWJitter.h rename to src/components/aocs/reaction_wheel_jitter.hpp index e934ffc54..3b3fd79e0 100644 --- a/src/components/aocs/RWJitter.h +++ b/src/components/aocs/reaction_wheel_jitter.hpp @@ -1,8 +1,11 @@ /* - * @file RWJitter.h + * @file reaction_wheel_jitter.hpp * @brief Class to calculate RW high-frequency jitter effect */ +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ + #pragma once #include #include @@ -118,3 +121,5 @@ class RWJitter { */ void CalcCoef(); }; + +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ From 3088e39d13c9530d37be6f210c326df5289d977c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:47:05 +0100 Subject: [PATCH 0301/1086] Rename RWModel --- src/components/CMakeLists.txt | 2 +- src/components/aocs/initialize_reaction_wheel.hpp | 2 +- .../aocs/{RWModel.cpp => reaction_wheel.cpp} | 4 ++-- .../aocs/{RWModel.h => reaction_wheel.hpp} | 13 +++++++------ 4 files changed, 11 insertions(+), 10 deletions(-) rename src/components/aocs/{RWModel.cpp => reaction_wheel.cpp} (99%) rename src/components/aocs/{RWModel.h => reaction_wheel.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f435cca39..200d86aa3 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -15,7 +15,7 @@ add_library(${PROJECT_NAME} STATIC aocs/magnetorquer.cpp aocs/initialize_magnetorquer.cpp aocs/reaction_wheel_ode.cpp - aocs/RWModel.cpp + aocs/reaction_wheel.cpp aocs/initialize_reaction_wheel.cpp aocs/reaction_wheel_jitter.cpp aocs/STT.cpp diff --git a/src/components/aocs/initialize_reaction_wheel.hpp b/src/components/aocs/initialize_reaction_wheel.hpp index 8589b3064..4e5315e14 100644 --- a/src/components/aocs/initialize_reaction_wheel.hpp +++ b/src/components/aocs/initialize_reaction_wheel.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ #define S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ -#include +#include /** * @fn InitRWModel diff --git a/src/components/aocs/RWModel.cpp b/src/components/aocs/reaction_wheel.cpp similarity index 99% rename from src/components/aocs/RWModel.cpp rename to src/components/aocs/reaction_wheel.cpp index 82622e372..0b09e7fad 100644 --- a/src/components/aocs/RWModel.cpp +++ b/src/components/aocs/reaction_wheel.cpp @@ -1,8 +1,8 @@ /* - * @file RWModel.cpp + * @file reaction_wheel.cpp * @brief Class to emulate Reaction Wheel */ -#include "RWModel.h" +#include "reaction_wheel.hpp" #include #include diff --git a/src/components/aocs/RWModel.h b/src/components/aocs/reaction_wheel.hpp similarity index 98% rename from src/components/aocs/RWModel.h rename to src/components/aocs/reaction_wheel.hpp index 0d918173a..5438d7b8c 100644 --- a/src/components/aocs/RWModel.h +++ b/src/components/aocs/reaction_wheel.hpp @@ -1,14 +1,14 @@ /* - * @file RWModel.h + * @file reaction_wheel.hpp * @brief Class to emulate Reaction Wheel */ -#ifndef __RWModel_H__ -#define __RWModel_H__ -#include -#include +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ #include +#include +#include #include #include #include @@ -234,4 +234,5 @@ class RWModel : public ComponentBase, public ILoggable { */ void Initialize(); }; -#endif //__RWModel_H__ + +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ From 3d0537f9eb8970975c0d1520877012467fc4de18 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 11:48:45 +0100 Subject: [PATCH 0302/1086] Rename STT --- src/components/CMakeLists.txt | 2 +- src/components/aocs/initialize_star_sensor.hpp | 2 +- src/components/aocs/{STT.cpp => star_sensor.cpp} | 4 ++-- src/components/aocs/{STT.h => star_sensor.hpp} | 11 +++++------ 4 files changed, 9 insertions(+), 10 deletions(-) rename src/components/aocs/{STT.cpp => star_sensor.cpp} (99%) rename src/components/aocs/{STT.h => star_sensor.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 200d86aa3..5f186113e 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -18,7 +18,7 @@ add_library(${PROJECT_NAME} STATIC aocs/reaction_wheel.cpp aocs/initialize_reaction_wheel.cpp aocs/reaction_wheel_jitter.cpp - aocs/STT.cpp + aocs/star_sensor.cpp aocs/initialize_star_sensor.cpp aocs/SunSensor.cpp aocs/initialize_sun_sensor.cpp diff --git a/src/components/aocs/initialize_star_sensor.hpp b/src/components/aocs/initialize_star_sensor.hpp index 7842d388c..20aceb1ec 100644 --- a/src/components/aocs/initialize_star_sensor.hpp +++ b/src/components/aocs/initialize_star_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ #define S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ -#include +#include /** * @fn InitSTT diff --git a/src/components/aocs/STT.cpp b/src/components/aocs/star_sensor.cpp similarity index 99% rename from src/components/aocs/STT.cpp rename to src/components/aocs/star_sensor.cpp index d00ea3cec..010af3511 100644 --- a/src/components/aocs/STT.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -1,9 +1,9 @@ /* - * @file STT.cpp + * @file star_sensor.cpp * @brief Class to emulate star tracker */ -#include "STT.h" +#include "star_sensor.hpp" #include #include diff --git a/src/components/aocs/STT.h b/src/components/aocs/star_sensor.hpp similarity index 98% rename from src/components/aocs/STT.h rename to src/components/aocs/star_sensor.hpp index cefb3f10c..77ece2540 100644 --- a/src/components/aocs/STT.h +++ b/src/components/aocs/star_sensor.hpp @@ -1,14 +1,12 @@ /* - * @file STT.h + * @file star_sensor.hpp * @brief Class to emulate star tracker */ #pragma once -#ifndef __STT_H__ -#define __STT_H__ - -#include +#ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ #include #include @@ -16,6 +14,7 @@ #include #include #include +#include #include #include "../base_classes/ComponentBase.h" @@ -206,4 +205,4 @@ class STT : public ComponentBase, public ILoggable { void Initialize(); }; -#endif +#endif // S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ From 95fdfd9ab66bd6e9918c4b886075df79ed0d6c65 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:33:03 +0100 Subject: [PATCH 0303/1086] Rename SunSensor --- src/components/CMakeLists.txt | 2 +- src/components/aocs/initialize_sun_sensor.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 -- src/components/aocs/{SunSensor.cpp => sun_sensor.cpp} | 4 ++-- src/components/aocs/{SunSensor.h => sun_sensor.hpp} | 11 +++++------ 5 files changed, 9 insertions(+), 12 deletions(-) rename src/components/aocs/{SunSensor.cpp => sun_sensor.cpp} (98%) rename src/components/aocs/{SunSensor.h => sun_sensor.hpp} (97%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 5f186113e..f59e2cc11 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -20,7 +20,7 @@ add_library(${PROJECT_NAME} STATIC aocs/reaction_wheel_jitter.cpp aocs/star_sensor.cpp aocs/initialize_star_sensor.cpp - aocs/SunSensor.cpp + aocs/sun_sensor.cpp aocs/initialize_sun_sensor.cpp aocs/gnss_receiver.cpp aocs/initialize_gnss_receiver.cpp diff --git a/src/components/aocs/initialize_sun_sensor.hpp b/src/components/aocs/initialize_sun_sensor.hpp index 41c7e87d5..24fb6c8f6 100644 --- a/src/components/aocs/initialize_sun_sensor.hpp +++ b/src/components/aocs/initialize_sun_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ #define S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ -#include +#include /** * @fn InitSunSensor diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 77ece2540..887e2233f 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -3,8 +3,6 @@ * @brief Class to emulate star tracker */ -#pragma once - #ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ #define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ diff --git a/src/components/aocs/SunSensor.cpp b/src/components/aocs/sun_sensor.cpp similarity index 98% rename from src/components/aocs/SunSensor.cpp rename to src/components/aocs/sun_sensor.cpp index 239a31318..9f075ce95 100644 --- a/src/components/aocs/SunSensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -1,9 +1,9 @@ /* - * @file SunSensor.cpp + * @file sun_sensor.cpp * @brief Class to emulate sun sensor */ -#include "SunSensor.h" +#include "sun_sensor.hpp" #include #include diff --git a/src/components/aocs/SunSensor.h b/src/components/aocs/sun_sensor.hpp similarity index 97% rename from src/components/aocs/SunSensor.h rename to src/components/aocs/sun_sensor.hpp index 015afdeda..f733ddfc4 100644 --- a/src/components/aocs/SunSensor.h +++ b/src/components/aocs/sun_sensor.hpp @@ -1,18 +1,17 @@ /* - * @file SunSensor.h + * @file sun_sensor.hpp * @brief Class to emulate sun sensor */ -#ifndef __SunSensor_H__ -#define __SunSensor_H__ - -#include +#ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ +#define S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ #include #include #include #include #include +#include #include "../base_classes/ComponentBase.h" @@ -140,4 +139,4 @@ class SunSensor : public ComponentBase, public ILoggable { void CalcSolarIlluminance(); }; -#endif //__SunSensor_H__ +#endif // S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ From fff54c1cdaa9b7aaa672b23e6bebbc92bcb03cb3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:38:16 +0100 Subject: [PATCH 0304/1086] Rename ComponentBase --- src/components/CMakeLists.txt | 2 +- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- .../{ComponentBase.cpp => component_base.cpp} | 4 ++-- .../base_classes/{ComponentBase.h => component_base.hpp} | 9 ++++++--- src/components/cdh/OBC.h | 2 +- src/components/examples/example_change_structure.hpp | 2 +- .../examples/example_i2c_controller_for_hils.hpp | 2 +- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 2 +- src/components/ideal_components/ForceGenerator.hpp | 2 +- src/components/ideal_components/TorqueGenerator.hpp | 2 +- src/components/mission/Telescope.h | 2 +- src/components/power/BAT.h | 2 +- src/components/power/PCU.h | 2 +- src/components/power/PCU_InitialStudy.h | 2 +- src/components/power/SAP.h | 2 +- src/components/propulsion/SimpleThruster.h | 2 +- 24 files changed, 30 insertions(+), 27 deletions(-) rename src/components/base_classes/{ComponentBase.cpp => component_base.cpp} (96%) rename src/components/base_classes/{ComponentBase.h => component_base.hpp} (93%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f59e2cc11..18f299f15 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -2,7 +2,7 @@ project(COMPONENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - base_classes/ComponentBase.cpp + base_classes/component_base.cpp base_classes/ObcCommunicationBase.cpp base_classes/I2cControllerCommunicationBase.cpp base_classes/ObcI2cTargetCommunicationBase.cpp diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 84495e7fe..2bd50df5f 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" using libra::Vector; diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index c0f14777d..2d8513b9a 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/SensorBase.h" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index e5e3f5a96..d22c2264e 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/SensorBase.h" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 6f08c0c16..15b913539 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -14,7 +14,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" const size_t kMtqDim = 3; //!< Dimension of magnetorquer diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index 5438d7b8c..e5cef37ae 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "reaction_wheel_jitter.hpp" #include "reaction_wheel_ode.hpp" diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 887e2233f..5b0864084 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -15,7 +15,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "dynamics/dynamics.hpp" /* diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index f733ddfc4..f474cac67 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /* * @class SunSensor diff --git a/src/components/base_classes/ComponentBase.cpp b/src/components/base_classes/component_base.cpp similarity index 96% rename from src/components/base_classes/ComponentBase.cpp rename to src/components/base_classes/component_base.cpp index 06d151606..1038b7244 100644 --- a/src/components/base_classes/ComponentBase.cpp +++ b/src/components/base_classes/component_base.cpp @@ -1,9 +1,9 @@ /** - * @file ComponentBase.cpp + * @file component_base.cpp * @brief Base class for component emulation. All components have to inherit this. */ -#include "ComponentBase.h" +#include "component_base.hpp" ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler) : clock_gen_(clock_gen) { power_port_ = new PowerPort(); diff --git a/src/components/base_classes/ComponentBase.h b/src/components/base_classes/component_base.hpp similarity index 93% rename from src/components/base_classes/ComponentBase.h rename to src/components/base_classes/component_base.hpp index d13da0a09..5d9a1b0fb 100644 --- a/src/components/base_classes/ComponentBase.h +++ b/src/components/base_classes/component_base.hpp @@ -1,13 +1,14 @@ /** - * @file ComponentBase.h + * @file component_base.hpp * @brief Base class for component emulation. All components have to inherit this. */ -#pragma once -#include +#ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ #include #include +#include #include "ITickable.h" @@ -86,3 +87,5 @@ class ComponentBase : public ITickable { ClockGenerator* clock_gen_; //!< Clock generator PowerPort* power_port_; //!< Power port }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ diff --git a/src/components/cdh/OBC.h b/src/components/cdh/OBC.h index 4279c111f..6ab702d3e 100644 --- a/src/components/cdh/OBC.h +++ b/src/components/cdh/OBC.h @@ -9,7 +9,7 @@ #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /* * @class OBC diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 68682d1a8..3ceb38f67 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -9,7 +9,7 @@ #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /** * @class ExampleChangeStructure diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index abc0ba023..5980532a9 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/I2cControllerCommunicationBase.h" /** diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 6b59c9dd6..ac48e1401 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/ObcI2cTargetCommunicationBase.h" /** diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 51a8ba8b4..0c5ea3119 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -5,7 +5,7 @@ #pragma once #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/ObcCommunicationBase.h" /** diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index ea28b697b..3f3fe37ea 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -6,7 +6,7 @@ #pragma once #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "../base_classes/IGPIOCompo.h" #include "../base_classes/ObcCommunicationBase.h" diff --git a/src/components/ideal_components/ForceGenerator.hpp b/src/components/ideal_components/ForceGenerator.hpp index eb6bfde5b..1a9b4babc 100644 --- a/src/components/ideal_components/ForceGenerator.hpp +++ b/src/components/ideal_components/ForceGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/ideal_components/TorqueGenerator.hpp b/src/components/ideal_components/TorqueGenerator.hpp index 2ad78ced3..bbf60365b 100644 --- a/src/components/ideal_components/TorqueGenerator.hpp +++ b/src/components/ideal_components/TorqueGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/mission/Telescope.h b/src/components/mission/Telescope.h index 83640524e..4260d21be 100644 --- a/src/components/mission/Telescope.h +++ b/src/components/mission/Telescope.h @@ -4,7 +4,7 @@ */ #pragma once -#include +#include #include #include diff --git a/src/components/power/BAT.h b/src/components/power/BAT.h index cc1beac04..a87637e20 100644 --- a/src/components/power/BAT.h +++ b/src/components/power/BAT.h @@ -8,7 +8,7 @@ #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /* * @class BAT diff --git a/src/components/power/PCU.h b/src/components/power/PCU.h index 6437788fe..f12ec961c 100644 --- a/src/components/power/PCU.h +++ b/src/components/power/PCU.h @@ -9,7 +9,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /* * @class PCU diff --git a/src/components/power/PCU_InitialStudy.h b/src/components/power/PCU_InitialStudy.h index 078d5554e..7692e3fae 100644 --- a/src/components/power/PCU_InitialStudy.h +++ b/src/components/power/PCU_InitialStudy.h @@ -8,7 +8,7 @@ #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" #include "BAT.h" #include "SAP.h" diff --git a/src/components/power/SAP.h b/src/components/power/SAP.h index b82f67490..99cd8ca31 100644 --- a/src/components/power/SAP.h +++ b/src/components/power/SAP.h @@ -10,7 +10,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" class SAP : public ComponentBase, public ILoggable { public: diff --git a/src/components/propulsion/SimpleThruster.h b/src/components/propulsion/SimpleThruster.h index a74e2b8eb..f1ec785ef 100644 --- a/src/components/propulsion/SimpleThruster.h +++ b/src/components/propulsion/SimpleThruster.h @@ -12,7 +12,7 @@ #include #include -#include "../base_classes/ComponentBase.h" +#include "../base_classes/component_base.hpp" /* * @class SimpleThruster From d56b0e02776fc6130fcb2715a5cbbf84da75fafe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:48:05 +0100 Subject: [PATCH 0305/1086] Rename I2cControllerCommunicationBase --- src/components/CMakeLists.txt | 2 +- ...ionBase.cpp => i2c_controller_communication_base.cpp} | 4 ++-- ...ationBase.h => i2c_controller_communication_base.hpp} | 9 +++++++-- .../examples/example_i2c_controller_for_hils.hpp | 2 +- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/components/base_classes/{I2cControllerCommunicationBase.cpp => i2c_controller_communication_base.cpp} (94%) rename src/components/base_classes/{I2cControllerCommunicationBase.h => i2c_controller_communication_base.hpp} (90%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 18f299f15..b81cf29e2 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC base_classes/component_base.cpp base_classes/ObcCommunicationBase.cpp - base_classes/I2cControllerCommunicationBase.cpp + base_classes/i2c_controller_communication_base.cpp base_classes/ObcI2cTargetCommunicationBase.cpp base_classes/ObcGpioBase.cpp diff --git a/src/components/base_classes/I2cControllerCommunicationBase.cpp b/src/components/base_classes/i2c_controller_communication_base.cpp similarity index 94% rename from src/components/base_classes/I2cControllerCommunicationBase.cpp rename to src/components/base_classes/i2c_controller_communication_base.cpp index 245609028..5b42929d2 100644 --- a/src/components/base_classes/I2cControllerCommunicationBase.cpp +++ b/src/components/base_classes/i2c_controller_communication_base.cpp @@ -1,8 +1,8 @@ /** - * @file I2cControllerCommunicationBase.cpp + * @file i2c_controller_communication_base.cpp * @brief This class simulates the I2C Controller communication with the I2C Target. */ -#include "I2cControllerCommunicationBase.h" +#include "i2c_controller_communication_base.hpp" #include diff --git a/src/components/base_classes/I2cControllerCommunicationBase.h b/src/components/base_classes/i2c_controller_communication_base.hpp similarity index 90% rename from src/components/base_classes/I2cControllerCommunicationBase.h rename to src/components/base_classes/i2c_controller_communication_base.hpp index 7953134ed..2f4425e86 100644 --- a/src/components/base_classes/I2cControllerCommunicationBase.h +++ b/src/components/base_classes/i2c_controller_communication_base.hpp @@ -1,8 +1,11 @@ /** - * @file I2cControllerCommunicationBase.h + * @file i2c_controller_communication_base.hpp * @brief This class simulates the I2C Controller communication with the I2C Target. */ -#pragma once + +#ifndef S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ + #include "../../interface/hils/hils_port_manager.hpp" #include "ObcCommunicationBase.h" @@ -60,3 +63,5 @@ class I2cControllerCommunicationBase { HilsPortManager* hils_port_manager_; //!< HILS port manager }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 5980532a9..e75fbbcb0 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -6,7 +6,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/I2cControllerCommunicationBase.h" +#include "../base_classes/i2c_controller_communication_base.hpp" /** * @class ExampleI2cControllerForHils From 465ba542a291add3da7ee41232838818e1b852fc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:54:19 +0100 Subject: [PATCH 0306/1086] Rename IGPIOBase --- .../{IGPIOCompo.h => interface_gpio_component.hpp} | 8 ++++++-- .../examples/example_serial_communication_with_obc.hpp | 2 +- src/interface/sils/ports/gpio_port.hpp | 2 +- 3 files changed, 8 insertions(+), 4 deletions(-) rename src/components/base_classes/{IGPIOCompo.h => interface_gpio_component.hpp} (71%) diff --git a/src/components/base_classes/IGPIOCompo.h b/src/components/base_classes/interface_gpio_component.hpp similarity index 71% rename from src/components/base_classes/IGPIOCompo.h rename to src/components/base_classes/interface_gpio_component.hpp index d3626ce51..de6691c7c 100644 --- a/src/components/base_classes/IGPIOCompo.h +++ b/src/components/base_classes/interface_gpio_component.hpp @@ -1,9 +1,11 @@ /** - * @file IGPIOCompo.h + * @file interface_gpio_component.hpp * @brief Interface class for components which have GPIO port */ -#pragma once +#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ +#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ + /** * @class IGPIOCompo * @brief Interface class for components which have GPIO port @@ -24,3 +26,5 @@ class IGPIOCompo { */ virtual void GPIOStateChanged(int port_id, bool isPosedge) = 0; }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 3f3fe37ea..71780166b 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -7,7 +7,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/IGPIOCompo.h" +#include "../base_classes/interface_gpio_component.hpp" #include "../base_classes/ObcCommunicationBase.h" /** diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/interface/sils/ports/gpio_port.hpp index b6796620e..0de8a12a7 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/interface/sils/ports/gpio_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ #define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ -#include +#include #define GPIO_HIGH true #define GPIO_LOW false From 6ba996df1cde05c847700242bb323221f2770594 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:54:39 +0100 Subject: [PATCH 0307/1086] Fix typo --- src/components/base_classes/component_base.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index 5d9a1b0fb..fd35e75fd 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -15,7 +15,7 @@ /** * @class ComponentBase * @brief Base class for component emulation. All components have to inherit this. - * @details CompoentBase ha clock and power on/off features + * @details ComponentBase ha clock and power on/off features */ class ComponentBase : public ITickable { public: From d9cc6fae1671213bf3511dd642a1587a6dff38a2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:54:57 +0100 Subject: [PATCH 0308/1086] Fix typo --- src/components/base_classes/component_base.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index fd35e75fd..4dd9e87a5 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -32,7 +32,7 @@ class ComponentBase : public ITickable { * @fn ComponentBase * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for normal update - * @param [in] clocl_gen: Clock generator + * @param [in] clock_gen: Clock generator * @param [in] power_port: Power port * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ From 2212cd44548ff93209d5e03769c442023bc9bb6d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 12:58:27 +0100 Subject: [PATCH 0309/1086] Rename InitializeSensorBase --- src/components/aocs/initialize_gyro_sensor.cpp | 2 +- src/components/aocs/initialize_magnetometer.cpp | 2 +- ...itializeSensorBase.hpp => initialize_sensor_base.hpp} | 9 ++++++--- ...SensorBase_tfs.hpp => initialize_sensor_base_tfs.hpp} | 8 ++++++-- 4 files changed, 14 insertions(+), 7 deletions(-) rename src/components/base_classes/{InitializeSensorBase.hpp => initialize_sensor_base.hpp} (72%) rename src/components/base_classes/{InitializeSensorBase_tfs.hpp => initialize_sensor_base_tfs.hpp} (89%) diff --git a/src/components/aocs/initialize_gyro_sensor.cpp b/src/components/aocs/initialize_gyro_sensor.cpp index 12795ac47..08a686efe 100644 --- a/src/components/aocs/initialize_gyro_sensor.cpp +++ b/src/components/aocs/initialize_gyro_sensor.cpp @@ -6,7 +6,7 @@ #include -#include "../base_classes/InitializeSensorBase.hpp" +#include "../base_classes/initialize_sensor_base.hpp" Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); diff --git a/src/components/aocs/initialize_magnetometer.cpp b/src/components/aocs/initialize_magnetometer.cpp index eb7c0871e..3c7658af7 100644 --- a/src/components/aocs/initialize_magnetometer.cpp +++ b/src/components/aocs/initialize_magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "initialize_magnetometer.hpp" -#include "../base_classes/InitializeSensorBase.hpp" +#include "../base_classes/initialize_sensor_base.hpp" #include "interface/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { diff --git a/src/components/base_classes/InitializeSensorBase.hpp b/src/components/base_classes/initialize_sensor_base.hpp similarity index 72% rename from src/components/base_classes/InitializeSensorBase.hpp rename to src/components/base_classes/initialize_sensor_base.hpp index 5bd3b5132..5f71af745 100644 --- a/src/components/base_classes/InitializeSensorBase.hpp +++ b/src/components/base_classes/initialize_sensor_base.hpp @@ -1,9 +1,10 @@ /** - * @file InitializeSensorBase.hpp + * @file initialize_sensor_base.hpp * @brief Initialize functions for SensorBase class */ -#pragma once +#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ #include "SensorBase.h" @@ -20,4 +21,6 @@ template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit = ""); -#include "InitializeSensorBase_tfs.hpp" +#include "initialize_sensor_base_tfs.hpp" + +#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ diff --git a/src/components/base_classes/InitializeSensorBase_tfs.hpp b/src/components/base_classes/initialize_sensor_base_tfs.hpp similarity index 89% rename from src/components/base_classes/InitializeSensorBase_tfs.hpp rename to src/components/base_classes/initialize_sensor_base_tfs.hpp index cb34e177d..f5722e3a0 100644 --- a/src/components/base_classes/InitializeSensorBase_tfs.hpp +++ b/src/components/base_classes/initialize_sensor_base_tfs.hpp @@ -1,9 +1,11 @@ /** - * @file InitializeSensorBase_tfs.hpp + * @file initialize_sensor_base_tfs.hpp * @brief Initialize functions for SensorBase class (template functions) */ -#pragma once +#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ +#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ + #include "interface/initialize/initialize_file_access.hpp" template @@ -48,3 +50,5 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl return sensor_base; } + +#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ From 63d15e9dc27c038a3b8977af113cb8fd99ed9d00 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:01:20 +0100 Subject: [PATCH 0310/1086] Rename ITickable --- src/components/base_classes/component_base.hpp | 2 +- .../{ITickable.h => interface_tickable.hpp} | 10 +++++++--- src/environment/global/clock_generator.hpp | 2 +- src/interface/hils/com_port_interface.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/base_classes/{ITickable.h => interface_tickable.hpp} (83%) diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index 4dd9e87a5..fea9c561d 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -10,7 +10,7 @@ #include #include -#include "ITickable.h" +#include "interface_tickable.hpp" /** * @class ComponentBase diff --git a/src/components/base_classes/ITickable.h b/src/components/base_classes/interface_tickable.hpp similarity index 83% rename from src/components/base_classes/ITickable.h rename to src/components/base_classes/interface_tickable.hpp index 4eddb12c0..4779220b9 100644 --- a/src/components/base_classes/ITickable.h +++ b/src/components/base_classes/interface_tickable.hpp @@ -1,9 +1,11 @@ /** - * @file ITickable.h + * @file interface_tickable.hpp * @brief Interface class for time update of components */ -#pragma once +#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ + /** * @class ITickable * @brief Interface class for time update of components @@ -36,4 +38,6 @@ class ITickable { protected: bool needs_fast_update_ = false; //!< Whether or not high-frequency disturbances need to be calculated -}; \ No newline at end of file +}; + +#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 2f15a734b..d83aa347a 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ #define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ -#include +#include #include diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index 5ec351247..386023ef1 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -8,7 +8,7 @@ #ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ #define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ -#include +#include #include #include From b9320d36d1eff1c651b0478edf6e886bedfe9383 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:04:45 +0100 Subject: [PATCH 0311/1086] Rename ObcCommunicationBase --- src/components/CMakeLists.txt | 2 +- .../base_classes/ObcI2cTargetCommunicationBase.h | 2 +- .../base_classes/i2c_controller_communication_base.hpp | 2 +- ...cCommunicationBase.cpp => obc_communication_base.cpp} | 4 ++-- ...ObcCommunicationBase.h => obc_communication_base.hpp} | 9 +++++++-- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 2 +- 7 files changed, 14 insertions(+), 9 deletions(-) rename src/components/base_classes/{ObcCommunicationBase.cpp => obc_communication_base.cpp} (98%) rename src/components/base_classes/{ObcCommunicationBase.h => obc_communication_base.hpp} (95%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index b81cf29e2..e02a67e08 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC base_classes/component_base.cpp - base_classes/ObcCommunicationBase.cpp + base_classes/obc_communication_base.cpp base_classes/i2c_controller_communication_base.cpp base_classes/ObcI2cTargetCommunicationBase.cpp base_classes/ObcGpioBase.cpp diff --git a/src/components/base_classes/ObcI2cTargetCommunicationBase.h b/src/components/base_classes/ObcI2cTargetCommunicationBase.h index d5e86d6c5..ef8599c40 100644 --- a/src/components/base_classes/ObcI2cTargetCommunicationBase.h +++ b/src/components/base_classes/ObcI2cTargetCommunicationBase.h @@ -5,7 +5,7 @@ #pragma once #include "../../interface/hils/hils_port_manager.hpp" #include "../cdh/OBC.h" -#include "ObcCommunicationBase.h" +#include "obc_communication_base.hpp" /** * @class ObcI2cTargetCommunicationBase diff --git a/src/components/base_classes/i2c_controller_communication_base.hpp b/src/components/base_classes/i2c_controller_communication_base.hpp index 2f4425e86..4942b3138 100644 --- a/src/components/base_classes/i2c_controller_communication_base.hpp +++ b/src/components/base_classes/i2c_controller_communication_base.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ #include "../../interface/hils/hils_port_manager.hpp" -#include "ObcCommunicationBase.h" +#include "obc_communication_base.hpp" /** * @class I2cControllerCommunicationBase diff --git a/src/components/base_classes/ObcCommunicationBase.cpp b/src/components/base_classes/obc_communication_base.cpp similarity index 98% rename from src/components/base_classes/ObcCommunicationBase.cpp rename to src/components/base_classes/obc_communication_base.cpp index 486980708..21df9bf6e 100644 --- a/src/components/base_classes/ObcCommunicationBase.cpp +++ b/src/components/base_classes/obc_communication_base.cpp @@ -1,9 +1,9 @@ /** - * @file ObcCommunicationBase.cpp + * @file obc_communication_base.cpp * @brief Base class for serial communication (e.g., UART) with OBC flight software */ -#include "ObcCommunicationBase.h" +#include "obc_communication_base.hpp" #include diff --git a/src/components/base_classes/ObcCommunicationBase.h b/src/components/base_classes/obc_communication_base.hpp similarity index 95% rename from src/components/base_classes/ObcCommunicationBase.h rename to src/components/base_classes/obc_communication_base.hpp index f70cddd99..7526437e5 100644 --- a/src/components/base_classes/ObcCommunicationBase.h +++ b/src/components/base_classes/obc_communication_base.hpp @@ -1,8 +1,11 @@ /** - * @file ObcCommunicationBase.h + * @file obc_communication_base.hpp * @brief Base class for serial communication (e.g., UART) with OBC flight software */ -#pragma once + +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ + #include #include "../cdh/OBC.h" @@ -124,3 +127,5 @@ class ObcCommunicationBase { */ virtual int GenerateTelemetry() = 0; }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 0c5ea3119..1a696aa57 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -6,7 +6,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/ObcCommunicationBase.h" +#include "../base_classes/obc_communication_base.hpp" /** * @class ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 71780166b..5a6627d31 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -8,7 +8,7 @@ #include "../base_classes/component_base.hpp" #include "../base_classes/interface_gpio_component.hpp" -#include "../base_classes/ObcCommunicationBase.h" +#include "../base_classes/obc_communication_base.hpp" /** * @class ExampleSerialCommunicationWithObc From 760418f37295dd55e994d29ac493e9613a8120a1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:07:19 +0100 Subject: [PATCH 0312/1086] Rename ObcGpioBase --- src/components/CMakeLists.txt | 2 +- .../base_classes/{ObcGpioBase.cpp => obc_gpio_base.cpp} | 4 ++-- .../base_classes/{ObcGpioBase.h => obc_gpio_base.hpp} | 9 +++++++-- 3 files changed, 10 insertions(+), 5 deletions(-) rename src/components/base_classes/{ObcGpioBase.cpp => obc_gpio_base.cpp} (90%) rename src/components/base_classes/{ObcGpioBase.h => obc_gpio_base.hpp} (87%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index e02a67e08..864a1e910 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC base_classes/obc_communication_base.cpp base_classes/i2c_controller_communication_base.cpp base_classes/ObcI2cTargetCommunicationBase.cpp - base_classes/ObcGpioBase.cpp + base_classes/obc_gpio_base.cpp aocs/gyro_sensor.cpp aocs/initialize_gyro_sensor.cpp diff --git a/src/components/base_classes/ObcGpioBase.cpp b/src/components/base_classes/obc_gpio_base.cpp similarity index 90% rename from src/components/base_classes/ObcGpioBase.cpp rename to src/components/base_classes/obc_gpio_base.cpp index 64e2512b4..a2151a1f0 100644 --- a/src/components/base_classes/ObcGpioBase.cpp +++ b/src/components/base_classes/obc_gpio_base.cpp @@ -1,10 +1,10 @@ /** - * @file ObcGpioBase.cpp + * @file obc_gpio_base.cpp * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ -#include "ObcGpioBase.h" +#include "obc_gpio_base.hpp" ObcGpioBase::ObcGpioBase(const std::vector port_id, OBC* obc) : port_id_(port_id), obc_(obc) { for (size_t i = 0; i < port_id_.size(); i++) { diff --git a/src/components/base_classes/ObcGpioBase.h b/src/components/base_classes/obc_gpio_base.hpp similarity index 87% rename from src/components/base_classes/ObcGpioBase.h rename to src/components/base_classes/obc_gpio_base.hpp index 067ea8929..5666d02a7 100644 --- a/src/components/base_classes/ObcGpioBase.h +++ b/src/components/base_classes/obc_gpio_base.hpp @@ -1,9 +1,12 @@ /** - * @file ObcGpioBase.h + * @file obc_gpio_base.hpp * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ -#pragma once + +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ + #include "../cdh/OBC.h" /** @@ -46,3 +49,5 @@ class ObcGpioBase { std::vector port_id_; //!< Port ID GPIO line OBC* obc_; //!< The communication target OBC }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ From c698ceb5ecc2e9e9ae12ede7e3f48fcb95bf5517 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:09:18 +0100 Subject: [PATCH 0313/1086] Rename ObcI2cTargetCommunicationase --- src/components/CMakeLists.txt | 2 +- ...ionBase.cpp => obc_i2c_target_communication_base.cpp} | 4 ++-- ...ationBase.h => obc_i2c_target_communication_base.hpp} | 9 +++++++-- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- 4 files changed, 11 insertions(+), 6 deletions(-) rename src/components/base_classes/{ObcI2cTargetCommunicationBase.cpp => obc_i2c_target_communication_base.cpp} (98%) rename src/components/base_classes/{ObcI2cTargetCommunicationBase.h => obc_i2c_target_communication_base.hpp} (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 864a1e910..4baee34ad 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC base_classes/component_base.cpp base_classes/obc_communication_base.cpp base_classes/i2c_controller_communication_base.cpp - base_classes/ObcI2cTargetCommunicationBase.cpp + base_classes/obc_i2c_target_communication_base.cpp base_classes/obc_gpio_base.cpp aocs/gyro_sensor.cpp diff --git a/src/components/base_classes/ObcI2cTargetCommunicationBase.cpp b/src/components/base_classes/obc_i2c_target_communication_base.cpp similarity index 98% rename from src/components/base_classes/ObcI2cTargetCommunicationBase.cpp rename to src/components/base_classes/obc_i2c_target_communication_base.cpp index 64d1bfda7..a56b57df3 100644 --- a/src/components/base_classes/ObcI2cTargetCommunicationBase.cpp +++ b/src/components/base_classes/obc_i2c_target_communication_base.cpp @@ -1,8 +1,8 @@ /** - * @file ObcI2cTargetCommunicationBase.cpp + * @file obc_i2c_target_communication_base.cpp * @brief Base class for I2C communication as target side with OBC flight software */ -#include "ObcI2cTargetCommunicationBase.h" +#include "obc_i2c_target_communication_base.hpp" #include diff --git a/src/components/base_classes/ObcI2cTargetCommunicationBase.h b/src/components/base_classes/obc_i2c_target_communication_base.hpp similarity index 94% rename from src/components/base_classes/ObcI2cTargetCommunicationBase.h rename to src/components/base_classes/obc_i2c_target_communication_base.hpp index ef8599c40..f49d376c3 100644 --- a/src/components/base_classes/ObcI2cTargetCommunicationBase.h +++ b/src/components/base_classes/obc_i2c_target_communication_base.hpp @@ -1,8 +1,11 @@ /** - * @file ObcI2cTargetCommunicationBase.h + * @file obc_i2c_target_communication_base.hpp * @brief Base class for I2C communication as target side with OBC flight software */ -#pragma once + +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ + #include "../../interface/hils/hils_port_manager.hpp" #include "../cdh/OBC.h" #include "obc_communication_base.hpp" @@ -117,3 +120,5 @@ class ObcI2cTargetCommunicationBase { OBC* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager }; + +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index ac48e1401..da2e8a870 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -7,7 +7,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/ObcI2cTargetCommunicationBase.h" +#include "../base_classes/obc_i2c_target_communication_base.hpp" /** * @class ExampleI2cTargetForHils From 5fe32e6d24407d04e94d90d10a77c66b2b82748a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:13:02 +0100 Subject: [PATCH 0314/1086] Rename SensorBase --- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/base_classes/initialize_sensor_base.hpp | 2 +- .../base_classes/{SensorBase.h => sensor_base.hpp} | 10 +++++++--- .../{SensorBase_tfs.hpp => sensor_base_tfs.hpp} | 7 +++++-- 5 files changed, 15 insertions(+), 8 deletions(-) rename src/components/base_classes/{SensorBase.h => sensor_base.hpp} (91%) rename src/components/base_classes/{SensorBase_tfs.hpp => sensor_base_tfs.hpp} (92%) diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index 2d8513b9a..f4a6cb1b9 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -11,7 +11,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/SensorBase.h" +#include "../base_classes/sensor_base.hpp" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index d22c2264e..65fd60af0 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -11,7 +11,7 @@ #include #include "../base_classes/component_base.hpp" -#include "../base_classes/SensorBase.h" +#include "../base_classes/sensor_base.hpp" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/base_classes/initialize_sensor_base.hpp b/src/components/base_classes/initialize_sensor_base.hpp index 5f71af745..1748dfeb8 100644 --- a/src/components/base_classes/initialize_sensor_base.hpp +++ b/src/components/base_classes/initialize_sensor_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ -#include "SensorBase.h" +#include "sensor_base.hpp" /** * @fn ReadSensorBaseInformation diff --git a/src/components/base_classes/SensorBase.h b/src/components/base_classes/sensor_base.hpp similarity index 91% rename from src/components/base_classes/SensorBase.h rename to src/components/base_classes/sensor_base.hpp index 1431ddc69..0e2631a2f 100644 --- a/src/components/base_classes/SensorBase.h +++ b/src/components/base_classes/sensor_base.hpp @@ -1,8 +1,10 @@ /** - * @file SensorBase.h + * @file sensor_base.hpp * @brief Base class for sensor emulation to add noises */ -#pragma once + +#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ +#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ #include #include @@ -69,4 +71,6 @@ class SensorBase { void RangeCheck(void); }; -#include "./SensorBase_tfs.hpp" // template function definisions. +#include "./sensor_base_tfs.hpp" // template function definisions. + +#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ \ No newline at end of file diff --git a/src/components/base_classes/SensorBase_tfs.hpp b/src/components/base_classes/sensor_base_tfs.hpp similarity index 92% rename from src/components/base_classes/SensorBase_tfs.hpp rename to src/components/base_classes/sensor_base_tfs.hpp index 2b2d84555..574cb3bf6 100644 --- a/src/components/base_classes/SensorBase_tfs.hpp +++ b/src/components/base_classes/sensor_base_tfs.hpp @@ -1,9 +1,10 @@ /** - * @file SensorBase.cpp + * @file sensor_base_tfs.hpp * @brief Base class for sensor emulation to add noises */ -#pragma once +#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ +#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ #include @@ -71,3 +72,5 @@ void SensorBase::RangeCheck(void) { } } } + +#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ \ No newline at end of file From 6ee2c750e7540730cd60700cd9a3cc2647936f4d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:19:01 +0100 Subject: [PATCH 0315/1086] Rename OBC --- src/components/CMakeLists.txt | 2 +- src/components/base_classes/obc_communication_base.hpp | 2 +- src/components/base_classes/obc_gpio_base.hpp | 2 +- .../base_classes/obc_i2c_target_communication_base.hpp | 2 +- src/components/cdh/OBC_C2A.h | 2 +- src/components/cdh/{OBC.cpp => obc.cpp} | 4 ++-- src/components/cdh/{OBC.h => obc.hpp} | 10 +++++++--- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 8 files changed, 15 insertions(+), 11 deletions(-) rename src/components/cdh/{OBC.cpp => obc.cpp} (99%) rename src/components/cdh/{OBC.h => obc.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 4baee34ad..e268d09fc 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -25,7 +25,7 @@ add_library(${PROJECT_NAME} STATIC aocs/gnss_receiver.cpp aocs/initialize_gnss_receiver.cpp - cdh/OBC.cpp + cdh/obc.cpp cdh/OBC_C2A.cpp communication/Antenna.cpp diff --git a/src/components/base_classes/obc_communication_base.hpp b/src/components/base_classes/obc_communication_base.hpp index 7526437e5..3425910a2 100644 --- a/src/components/base_classes/obc_communication_base.hpp +++ b/src/components/base_classes/obc_communication_base.hpp @@ -8,7 +8,7 @@ #include -#include "../cdh/OBC.h" +#include "../cdh/obc.hpp" /** * @enum OBC_COM_UART_MODE diff --git a/src/components/base_classes/obc_gpio_base.hpp b/src/components/base_classes/obc_gpio_base.hpp index 5666d02a7..bd1d84d48 100644 --- a/src/components/base_classes/obc_gpio_base.hpp +++ b/src/components/base_classes/obc_gpio_base.hpp @@ -7,7 +7,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ -#include "../cdh/OBC.h" +#include "../cdh/obc.hpp" /** * @class ObcGpioBase diff --git a/src/components/base_classes/obc_i2c_target_communication_base.hpp b/src/components/base_classes/obc_i2c_target_communication_base.hpp index f49d376c3..81b6810c5 100644 --- a/src/components/base_classes/obc_i2c_target_communication_base.hpp +++ b/src/components/base_classes/obc_i2c_target_communication_base.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ #include "../../interface/hils/hils_port_manager.hpp" -#include "../cdh/OBC.h" +#include "../cdh/obc.hpp" #include "obc_communication_base.hpp" /** diff --git a/src/components/cdh/OBC_C2A.h b/src/components/cdh/OBC_C2A.h index 7963aba3f..9bce2e89d 100644 --- a/src/components/cdh/OBC_C2A.h +++ b/src/components/cdh/OBC_C2A.h @@ -6,7 +6,7 @@ #pragma once #include -#include "OBC.h" +#include "obc.hpp" /* * @class OBC_C2A diff --git a/src/components/cdh/OBC.cpp b/src/components/cdh/obc.cpp similarity index 99% rename from src/components/cdh/OBC.cpp rename to src/components/cdh/obc.cpp index a1d70c2af..9e0a18131 100644 --- a/src/components/cdh/OBC.cpp +++ b/src/components/cdh/obc.cpp @@ -1,8 +1,8 @@ /* - * @file OBC.cpp + * @file obc.cpp * @brief Class to emulate on board computer */ -#include "OBC.h" +#include "obc.hpp" OBC::OBC(ClockGenerator* clock_gen) : ComponentBase(1, clock_gen) { Initialize(); } diff --git a/src/components/cdh/OBC.h b/src/components/cdh/obc.hpp similarity index 98% rename from src/components/cdh/OBC.h rename to src/components/cdh/obc.hpp index 6ab702d3e..fffc55518 100644 --- a/src/components/cdh/OBC.h +++ b/src/components/cdh/obc.hpp @@ -1,12 +1,14 @@ /* - * @file OBC.h + * @file obc.hpp * @brief Class to emulate on board computer */ -#pragma once + +#ifndef S2E_COMPONENTS_CDH_OBC_H_ +#define S2E_COMPONENTS_CDH_OBC_H_ + #include #include #include - #include #include "../base_classes/component_base.hpp" @@ -203,3 +205,5 @@ class OBC : public ComponentBase { std::map i2c_com_ports_; //!< I2C ports std::map gpio_ports_; //!< GPIO ports }; + +#endif // S2E_COMPONENTS_CDH_OBC_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 89030855d..8e786437b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include +#include #include #include From 20a54414c43fb447c2b8d85653f12e3d08ef3af0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:20:43 +0100 Subject: [PATCH 0316/1086] Rename OBC_C2A --- src/components/CMakeLists.txt | 2 +- src/components/aocs/gyro_sensor.cpp | 2 +- src/components/cdh/{OBC_C2A.cpp => obc_c2a.cpp} | 4 ++-- src/components/cdh/{OBC_C2A.h => obc_c2a.hpp} | 8 ++++++-- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/cdh/{OBC_C2A.cpp => obc_c2a.cpp} (99%) rename src/components/cdh/{OBC_C2A.h => obc_c2a.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index e268d09fc..63656fc17 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -26,7 +26,7 @@ add_library(${PROJECT_NAME} STATIC aocs/initialize_gnss_receiver.cpp cdh/obc.cpp - cdh/OBC_C2A.cpp + cdh/obc_c2a.cpp communication/Antenna.cpp communication/AntennaRadiationPattern.cpp diff --git a/src/components/aocs/gyro_sensor.cpp b/src/components/aocs/gyro_sensor.cpp index 9741cb2a7..a8fb285f0 100644 --- a/src/components/aocs/gyro_sensor.cpp +++ b/src/components/aocs/gyro_sensor.cpp @@ -5,7 +5,7 @@ #include "gyro_sensor.hpp" -#include "../cdh/OBC_C2A.h" +#include "../cdh/obc_c2a.hpp" Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) diff --git a/src/components/cdh/OBC_C2A.cpp b/src/components/cdh/obc_c2a.cpp similarity index 99% rename from src/components/cdh/OBC_C2A.cpp rename to src/components/cdh/obc_c2a.cpp index 80270583a..b565e4fe6 100644 --- a/src/components/cdh/OBC_C2A.cpp +++ b/src/components/cdh/obc_c2a.cpp @@ -1,9 +1,9 @@ /* - * @file OBC_C2A.cpp + * @file obc_c2a.cpp * @brief Class to emulate on board computer with C2A flight software */ -#include "OBC_C2A.h" +#include "obc_c2a.hpp" #ifdef USE_C2A #include "src_core/System/TaskManager/task_dispatcher.h" diff --git a/src/components/cdh/OBC_C2A.h b/src/components/cdh/obc_c2a.hpp similarity index 98% rename from src/components/cdh/OBC_C2A.h rename to src/components/cdh/obc_c2a.hpp index 9bce2e89d..9fad1d1fa 100644 --- a/src/components/cdh/OBC_C2A.h +++ b/src/components/cdh/obc_c2a.hpp @@ -1,9 +1,11 @@ /* - * @file OBC_C2A.h + * @file obc_c2a.hpp * @brief Class to emulate on board computer with C2A flight software */ -#pragma once +#ifndef S2E_COMPONENTS_CDH_OBC_C2A_H_ +#define S2E_COMPONENTS_CDH_OBC_C2A_H_ + #include #include "obc.hpp" @@ -284,3 +286,5 @@ int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned // GPIO int OBC_C2A_GpioWrite(int port_id, const bool is_high); bool OBC_C2A_GpioRead(int port_id); // return false when the port_id is not used + +#endif // S2E_COMPONENTS_CDH_OBC_C2A_H_ From 3743acc645f3305a9d48b36ae5f74e8b78cfa7c6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:23:05 +0100 Subject: [PATCH 0317/1086] Rename Antenna --- src/components/CMakeLists.txt | 2 +- src/components/communication/AntennaRadiationPattern.cpp | 2 +- src/components/communication/GScalculator.h | 2 +- src/components/communication/InitAntenna.hpp | 2 +- src/components/communication/{Antenna.cpp => antenna.cpp} | 4 ++-- src/components/communication/{Antenna.hpp => antenna.hpp} | 8 ++++++-- .../sample_ground_station/sample_ground_station.hpp | 2 +- 7 files changed, 13 insertions(+), 9 deletions(-) rename src/components/communication/{Antenna.cpp => antenna.cpp} (98%) rename src/components/communication/{Antenna.hpp => antenna.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 63656fc17..0d4b6df05 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -28,7 +28,7 @@ add_library(${PROJECT_NAME} STATIC cdh/obc.cpp cdh/obc_c2a.cpp - communication/Antenna.cpp + communication/antenna.cpp communication/AntennaRadiationPattern.cpp communication/InitAntenna.cpp communication/GScalculator.cpp diff --git a/src/components/communication/AntennaRadiationPattern.cpp b/src/components/communication/AntennaRadiationPattern.cpp index 63575eaa0..fedd49cad 100644 --- a/src/components/communication/AntennaRadiationPattern.cpp +++ b/src/components/communication/AntennaRadiationPattern.cpp @@ -1,5 +1,5 @@ /* - * @file Antenna.cpp + * @file antenna.cpp * @brief Component emulation: RF antenna */ diff --git a/src/components/communication/GScalculator.h b/src/components/communication/GScalculator.h index 163e00eca..d2f6f7f41 100644 --- a/src/components/communication/GScalculator.h +++ b/src/components/communication/GScalculator.h @@ -8,7 +8,7 @@ #include -#include +#include #include #include #include diff --git a/src/components/communication/InitAntenna.hpp b/src/components/communication/InitAntenna.hpp index 748361199..820275f41 100644 --- a/src/components/communication/InitAntenna.hpp +++ b/src/components/communication/InitAntenna.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitAntenna diff --git a/src/components/communication/Antenna.cpp b/src/components/communication/antenna.cpp similarity index 98% rename from src/components/communication/Antenna.cpp rename to src/components/communication/antenna.cpp index 2ccb8aede..0e24cea43 100644 --- a/src/components/communication/Antenna.cpp +++ b/src/components/communication/antenna.cpp @@ -1,9 +1,9 @@ /* - * @file Antenna.cpp + * @file antenna.cpp * @brief Component emulation: RF antenna */ -#include "Antenna.hpp" +#include "antenna.hpp" #include #include diff --git a/src/components/communication/Antenna.hpp b/src/components/communication/antenna.hpp similarity index 96% rename from src/components/communication/Antenna.hpp rename to src/components/communication/antenna.hpp index 0b4b8dbc8..4850b6430 100644 --- a/src/components/communication/Antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -1,9 +1,11 @@ /* - * @file Antenna.hpp + * @file antenna.hpp * @brief Component emulation: RF antenna */ -#pragma once +#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ +#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ + #include #include using libra::Quaternion; @@ -147,3 +149,5 @@ class Antenna { }; AntennaGainModel SetAntennaGainModel(const std::string gain_model_name); + +#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index bcd49d668..55e675659 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -8,7 +8,7 @@ #include -#include +#include #include #include From 03a038116c3b1962fb8782f5f23967a1dd51cf5e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:25:26 +0100 Subject: [PATCH 0318/1086] Rename AntennaRadiationPattern --- src/components/CMakeLists.txt | 2 +- src/components/communication/antenna.hpp | 2 +- ...adiationPattern.cpp => antenna_radiation_pattern.cpp} | 9 ++++----- ...adiationPattern.hpp => antenna_radiation_pattern.hpp} | 8 ++++++-- 4 files changed, 12 insertions(+), 9 deletions(-) rename src/components/communication/{AntennaRadiationPattern.cpp => antenna_radiation_pattern.cpp} (92%) rename src/components/communication/{AntennaRadiationPattern.hpp => antenna_radiation_pattern.hpp} (89%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 0d4b6df05..641daeb7d 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -29,7 +29,7 @@ add_library(${PROJECT_NAME} STATIC cdh/obc_c2a.cpp communication/antenna.cpp - communication/AntennaRadiationPattern.cpp + communication/antenna_radiation_pattern.cpp communication/InitAntenna.cpp communication/GScalculator.cpp communication/InitGsCalculator.cpp diff --git a/src/components/communication/antenna.hpp b/src/components/communication/antenna.hpp index 4850b6430..33fd19507 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -12,7 +12,7 @@ using libra::Quaternion; using libra::Vector; #include -#include "./AntennaRadiationPattern.hpp" +#include "./antenna_radiation_pattern.hpp" /* * @enum AntennaGainModel diff --git a/src/components/communication/AntennaRadiationPattern.cpp b/src/components/communication/antenna_radiation_pattern.cpp similarity index 92% rename from src/components/communication/AntennaRadiationPattern.cpp rename to src/components/communication/antenna_radiation_pattern.cpp index fedd49cad..6da080c2d 100644 --- a/src/components/communication/AntennaRadiationPattern.cpp +++ b/src/components/communication/antenna_radiation_pattern.cpp @@ -1,14 +1,13 @@ /* - * @file antenna.cpp - * @brief Component emulation: RF antenna + * @file antenna_radiation_pattern.cpp + * @brief Class to manage antenna radiation pattern */ -#include "AntennaRadiationPattern.hpp" - -#include +#include "antenna_radiation_pattern.hpp" #include #include +#include AntennaRadiationPattern::AntennaRadiationPattern() { gain_dBi_.assign(length_theta_, std::vector(length_phi_, 0.0)); } diff --git a/src/components/communication/AntennaRadiationPattern.hpp b/src/components/communication/antenna_radiation_pattern.hpp similarity index 89% rename from src/components/communication/AntennaRadiationPattern.hpp rename to src/components/communication/antenna_radiation_pattern.hpp index b180b99b1..697c877cf 100644 --- a/src/components/communication/AntennaRadiationPattern.hpp +++ b/src/components/communication/antenna_radiation_pattern.hpp @@ -1,9 +1,11 @@ /* - * @file AntennaRadiationPattern.hpp + * @file antenna_radiation_pattern.hpp * @brief Class to manage antenna radiation pattern */ -#pragma once +#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ +#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ + #include #include #include @@ -59,3 +61,5 @@ class AntennaRadiationPattern { std::vector> gain_dBi_; //!< Antenna gain table [dBi] }; + +#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ From 5a6209602495a6c7a160b6782e1286bcbc69d5c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 13:28:40 +0100 Subject: [PATCH 0319/1086] Rename GSCalculator --- src/components/CMakeLists.txt | 2 +- src/components/communication/InitGsCalculator.hpp | 2 +- ...Scalculator.cpp => ground_station_calculator.cpp} | 4 ++-- ...{GScalculator.h => ground_station_calculator.hpp} | 12 +++++++----- .../sample_ground_station/sample_ground_station.hpp | 2 +- 5 files changed, 12 insertions(+), 10 deletions(-) rename src/components/communication/{GScalculator.cpp => ground_station_calculator.cpp} (98%) rename src/components/communication/{GScalculator.h => ground_station_calculator.hpp} (95%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 641daeb7d..462423ada 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -31,7 +31,7 @@ add_library(${PROJECT_NAME} STATIC communication/antenna.cpp communication/antenna_radiation_pattern.cpp communication/InitAntenna.cpp - communication/GScalculator.cpp + communication/ground_station_calculator.cpp communication/InitGsCalculator.cpp examples/example_change_structure.cpp diff --git a/src/components/communication/InitGsCalculator.hpp b/src/components/communication/InitGsCalculator.hpp index 108dbed23..5bfd0b5b8 100644 --- a/src/components/communication/InitGsCalculator.hpp +++ b/src/components/communication/InitGsCalculator.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include /* * @fn InitGscalculator diff --git a/src/components/communication/GScalculator.cpp b/src/components/communication/ground_station_calculator.cpp similarity index 98% rename from src/components/communication/GScalculator.cpp rename to src/components/communication/ground_station_calculator.cpp index 7faa095a0..df178a72a 100644 --- a/src/components/communication/GScalculator.cpp +++ b/src/components/communication/ground_station_calculator.cpp @@ -1,9 +1,9 @@ /* - * @file GScalculator.cpp + * @file ground_station_calculator.cpp * @brief Emulation of analysis and calculation for Ground Stations */ -#include "GScalculator.h" +#include "ground_station_calculator.hpp" #include #include diff --git a/src/components/communication/GScalculator.h b/src/components/communication/ground_station_calculator.hpp similarity index 95% rename from src/components/communication/GScalculator.h rename to src/components/communication/ground_station_calculator.hpp index d2f6f7f41..d50cc6373 100644 --- a/src/components/communication/GScalculator.h +++ b/src/components/communication/ground_station_calculator.hpp @@ -1,19 +1,19 @@ /* - * @file GScalculator.h + * @file ground_station_calculator.hpp * @brief Emulation of analysis and calculation for Ground Stations * @note TODO: This class is not `Component`. We need to move this to `Analysis` category and use this as library in future. */ -#pragma once +#ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ +#define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ -#include - -#include #include #include #include +#include #include #include +#include #include using libra::Matrix; @@ -137,3 +137,5 @@ class GScalculator : public ILoggable { */ double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); }; + +#endif // S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 55e675659..c047f524c 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ -#include +#include #include #include From 5f632c5bbea14d8bbae3673f742b70d6ea2f3dcf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:02:31 +0100 Subject: [PATCH 0320/1086] Rename InitAntenna --- src/components/CMakeLists.txt | 2 +- .../{InitAntenna.cpp => initialize_antenna.cpp} | 4 ++-- .../{InitAntenna.hpp => initialize_antenna.hpp} | 8 ++++++-- .../sample_ground_station_components.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/components/communication/{InitAntenna.cpp => initialize_antenna.cpp} (98%) rename src/components/communication/{InitAntenna.hpp => initialize_antenna.hpp} (60%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 462423ada..9e98beb71 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -30,7 +30,7 @@ add_library(${PROJECT_NAME} STATIC communication/antenna.cpp communication/antenna_radiation_pattern.cpp - communication/InitAntenna.cpp + communication/initialize_antenna.cpp communication/ground_station_calculator.cpp communication/InitGsCalculator.cpp diff --git a/src/components/communication/InitAntenna.cpp b/src/components/communication/initialize_antenna.cpp similarity index 98% rename from src/components/communication/InitAntenna.cpp rename to src/components/communication/initialize_antenna.cpp index 4aa45edab..9d2cb17b8 100644 --- a/src/components/communication/InitAntenna.cpp +++ b/src/components/communication/initialize_antenna.cpp @@ -1,10 +1,10 @@ /* - * @file InitAntenna.cpp + * @file initialize_antenna.cpp * @brief Initialize function for Antenna */ #define _CRT_SECURE_NO_WARNINGS -#include "InitAntenna.hpp" +#include "initialize_antenna.hpp" #include diff --git a/src/components/communication/InitAntenna.hpp b/src/components/communication/initialize_antenna.hpp similarity index 60% rename from src/components/communication/InitAntenna.hpp rename to src/components/communication/initialize_antenna.hpp index 820275f41..94aaaaea6 100644 --- a/src/components/communication/InitAntenna.hpp +++ b/src/components/communication/initialize_antenna.hpp @@ -1,8 +1,10 @@ /* - * @file InitAntenna.hpp + * @file initialize_antenna.hpp * @brief Initialize function for Antenna */ -#pragma once + +#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ +#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ #include @@ -13,3 +15,5 @@ * @param [in] file_name: Path to initialize file */ Antenna InitAntenna(const int antenna_id, const std::string file_name); + +#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 85c1ab70f..a981b4613 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ -#include +#include #include /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 8e786437b..b22f8cb1a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -10,7 +10,7 @@ #include #include -#include +#include #include #include #include From b7fd136d2afc1e4d771951bde04865bde7524489 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:07:08 +0100 Subject: [PATCH 0321/1086] Rename InitGsCalculator --- src/components/CMakeLists.txt | 2 +- ...ulator.cpp => initialize_ground_station_calculator.cpp} | 4 ++-- ...ulator.hpp => initialize_ground_station_calculator.hpp} | 7 +++++-- .../sample_ground_station_components.hpp | 2 +- 4 files changed, 9 insertions(+), 6 deletions(-) rename src/components/communication/{InitGsCalculator.cpp => initialize_ground_station_calculator.cpp} (92%) rename src/components/communication/{InitGsCalculator.hpp => initialize_ground_station_calculator.hpp} (53%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 9e98beb71..08c011c07 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -32,7 +32,7 @@ add_library(${PROJECT_NAME} STATIC communication/antenna_radiation_pattern.cpp communication/initialize_antenna.cpp communication/ground_station_calculator.cpp - communication/InitGsCalculator.cpp + communication/initialize_ground_station_calculator.cpp examples/example_change_structure.cpp examples/example_serial_communication_with_obc.cpp diff --git a/src/components/communication/InitGsCalculator.cpp b/src/components/communication/initialize_ground_station_calculator.cpp similarity index 92% rename from src/components/communication/InitGsCalculator.cpp rename to src/components/communication/initialize_ground_station_calculator.cpp index 6e17e6ac8..149fca923 100644 --- a/src/components/communication/InitGsCalculator.cpp +++ b/src/components/communication/initialize_ground_station_calculator.cpp @@ -1,10 +1,10 @@ /* - * @file InitGscalculator.cpp + * @file initialize_ground_station_calculator.hpp.cpp * @brief Initialize function for Ground Station Calculator */ #define _CRT_SECURE_NO_WARNINGS -#include "InitGsCalculator.hpp" +#include "initialize_ground_station_calculator.hpp" #include diff --git a/src/components/communication/InitGsCalculator.hpp b/src/components/communication/initialize_ground_station_calculator.hpp similarity index 53% rename from src/components/communication/InitGsCalculator.hpp rename to src/components/communication/initialize_ground_station_calculator.hpp index 5bfd0b5b8..39fa2337a 100644 --- a/src/components/communication/InitGsCalculator.hpp +++ b/src/components/communication/initialize_ground_station_calculator.hpp @@ -1,9 +1,10 @@ /* - * @file InitGscalculator.hpp + * @file initialize_ground_station_calculator.hpp.hpp * @brief Initialize function for Ground Station Calculator */ -#pragma once +#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ +#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ #include @@ -14,3 +15,5 @@ */ GScalculator InitGScalculator(const std::string fname); + +#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index a981b4613..b725eb8ae 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ #include -#include +#include /** * @class SampleGSComponents From e45c20c35e4dcb87a4da947502f54b14e78e6d77 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:10:41 +0100 Subject: [PATCH 0322/1086] Rename ForceGenerator --- src/components/CMakeLists.txt | 2 +- .../ideal_components/InitializeForceGenerator.hpp | 2 +- .../{ForceGenerator.cpp => force_generator.cpp} | 4 ++-- .../{ForceGenerator.hpp => force_generator.hpp} | 11 +++++++---- 4 files changed, 11 insertions(+), 8 deletions(-) rename src/components/ideal_components/{ForceGenerator.cpp => force_generator.cpp} (98%) rename src/components/ideal_components/{ForceGenerator.hpp => force_generator.hpp} (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 08c011c07..7d1801d37 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -40,7 +40,7 @@ add_library(${PROJECT_NAME} STATIC examples/example_i2c_controller_for_hils.cpp examples/example_i2c_target_for_hils.cpp - ideal_components/ForceGenerator.cpp + ideal_components/force_generator.cpp ideal_components/InitializeForceGenerator.cpp ideal_components/TorqueGenerator.cpp ideal_components/InitializeTorqueGenerator.cpp diff --git a/src/components/ideal_components/InitializeForceGenerator.hpp b/src/components/ideal_components/InitializeForceGenerator.hpp index 73cc9b540..68d131ed7 100644 --- a/src/components/ideal_components/InitializeForceGenerator.hpp +++ b/src/components/ideal_components/InitializeForceGenerator.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include "ForceGenerator.hpp" +#include "force_generator.hpp" /** * @fn InitializeForceGenerator diff --git a/src/components/ideal_components/ForceGenerator.cpp b/src/components/ideal_components/force_generator.cpp similarity index 98% rename from src/components/ideal_components/ForceGenerator.cpp rename to src/components/ideal_components/force_generator.cpp index e0f050a4b..a88bd0e7e 100644 --- a/src/components/ideal_components/ForceGenerator.cpp +++ b/src/components/ideal_components/force_generator.cpp @@ -1,9 +1,9 @@ /* - * @file ForceGenerator.cpp + * @file force_generator.cpp * @brief Ideal component which can generate force for control algorithm test */ -#include "ForceGenerator.hpp" +#include "force_generator.hpp" #include diff --git a/src/components/ideal_components/ForceGenerator.hpp b/src/components/ideal_components/force_generator.hpp similarity index 94% rename from src/components/ideal_components/ForceGenerator.hpp rename to src/components/ideal_components/force_generator.hpp index 1a9b4babc..e753dd9f0 100644 --- a/src/components/ideal_components/ForceGenerator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -1,15 +1,16 @@ /* - * @file ForceGenerator.hpp + * @file force_generator.hpp * @brief Ideal component which can generate force for control algorithm test */ -#pragma once -#include -#include +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ #include #include +#include #include +#include /* * @class ForceGenerator @@ -113,3 +114,5 @@ class ForceGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; + +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ From fe2f60ecb27a95ef9378497ede6e0862a68e1883 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:12:29 +0100 Subject: [PATCH 0323/1086] Rename InitializeForceGenerator --- src/components/CMakeLists.txt | 2 +- ...eForceGenerator.cpp => initialize_force_generator.cpp} | 4 ++-- ...eForceGenerator.hpp => initialize_force_generator.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/ideal_components/{InitializeForceGenerator.cpp => initialize_force_generator.cpp} (92%) rename src/components/ideal_components/{InitializeForceGenerator.hpp => initialize_force_generator.hpp} (63%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 7d1801d37..41468e546 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -41,7 +41,7 @@ add_library(${PROJECT_NAME} STATIC examples/example_i2c_target_for_hils.cpp ideal_components/force_generator.cpp - ideal_components/InitializeForceGenerator.cpp + ideal_components/initialize_force_generator.cpp ideal_components/TorqueGenerator.cpp ideal_components/InitializeTorqueGenerator.cpp diff --git a/src/components/ideal_components/InitializeForceGenerator.cpp b/src/components/ideal_components/initialize_force_generator.cpp similarity index 92% rename from src/components/ideal_components/InitializeForceGenerator.cpp rename to src/components/ideal_components/initialize_force_generator.cpp index 4f55aecf2..1f9bf19ac 100644 --- a/src/components/ideal_components/InitializeForceGenerator.cpp +++ b/src/components/ideal_components/initialize_force_generator.cpp @@ -1,8 +1,8 @@ /* - * @file InitializeForceGenerator.cpp + * @file initialize_force_generator.cpp * @brief Initialize function for ForceGenerator */ -#include "InitializeForceGenerator.hpp" +#include "initialize_force_generator.hpp" #include diff --git a/src/components/ideal_components/InitializeForceGenerator.hpp b/src/components/ideal_components/initialize_force_generator.hpp similarity index 63% rename from src/components/ideal_components/InitializeForceGenerator.hpp rename to src/components/ideal_components/initialize_force_generator.hpp index 68d131ed7..639aa15f6 100644 --- a/src/components/ideal_components/InitializeForceGenerator.hpp +++ b/src/components/ideal_components/initialize_force_generator.hpp @@ -1,8 +1,10 @@ /* - * @file InitializeForceGenerator.hpp + * @file initialize_force_generator.hpp * @brief Initialize function for ForceGenerator */ -#pragma once + +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ #include "force_generator.hpp" @@ -14,3 +16,5 @@ * @param [in] dynamics: Dynamics information */ ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); + +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index b22f8cb1a..df14c0d8f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -11,7 +11,7 @@ #include #include -#include +#include #include #include #include From 7ed18d538b72f1952a856949be0f0346194e3e52 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:14:01 +0100 Subject: [PATCH 0324/1086] Rename InitializeTorqueGenerator --- src/components/CMakeLists.txt | 2 +- ...orqueGenerator.cpp => initialize_torque_generator.cpp} | 4 ++-- ...orqueGenerator.hpp => initialize_torque_generator.hpp} | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) rename src/components/ideal_components/{InitializeTorqueGenerator.cpp => initialize_torque_generator.cpp} (92%) rename src/components/ideal_components/{InitializeTorqueGenerator.hpp => initialize_torque_generator.hpp} (63%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 41468e546..d70bd78cc 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -43,7 +43,7 @@ add_library(${PROJECT_NAME} STATIC ideal_components/force_generator.cpp ideal_components/initialize_force_generator.cpp ideal_components/TorqueGenerator.cpp - ideal_components/InitializeTorqueGenerator.cpp + ideal_components/initialize_torque_generator.cpp mission/Telescope.cpp mission/InitTelescope.cpp diff --git a/src/components/ideal_components/InitializeTorqueGenerator.cpp b/src/components/ideal_components/initialize_torque_generator.cpp similarity index 92% rename from src/components/ideal_components/InitializeTorqueGenerator.cpp rename to src/components/ideal_components/initialize_torque_generator.cpp index c5abfce47..1e8630497 100644 --- a/src/components/ideal_components/InitializeTorqueGenerator.cpp +++ b/src/components/ideal_components/initialize_torque_generator.cpp @@ -1,8 +1,8 @@ /* - * @file InitializeTorqueGenerator.cpp + * @file initialize_torque_generator.cpp * @brief Initialize function for TorqueGenerator */ -#include "InitializeTorqueGenerator.hpp" +#include "initialize_torque_generator.hpp" #include diff --git a/src/components/ideal_components/InitializeTorqueGenerator.hpp b/src/components/ideal_components/initialize_torque_generator.hpp similarity index 63% rename from src/components/ideal_components/InitializeTorqueGenerator.hpp rename to src/components/ideal_components/initialize_torque_generator.hpp index 7e26c8866..9e0c1d796 100644 --- a/src/components/ideal_components/InitializeTorqueGenerator.hpp +++ b/src/components/ideal_components/initialize_torque_generator.hpp @@ -1,8 +1,10 @@ /* - * @file InitializeTorqueGenerator.hpp + * @file initialize_torque_generator.hpp * @brief Initialize function for TorqueGenerator */ -#pragma once + +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ #include "TorqueGenerator.hpp" @@ -14,3 +16,5 @@ * @param [in] dynamics: Dynamics information */ TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); + +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index df14c0d8f..a34a20fff 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include #include #include From ac4b8a3c8dfa8cf954faddaa4d867bde518de88e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:15:41 +0100 Subject: [PATCH 0325/1086] Rename TorqueGenerator --- src/components/CMakeLists.txt | 2 +- .../ideal_components/initialize_torque_generator.hpp | 2 +- .../{TorqueGenerator.cpp => torque_generator.cpp} | 4 ++-- .../{TorqueGenerator.hpp => torque_generator.hpp} | 11 +++++++---- 4 files changed, 11 insertions(+), 8 deletions(-) rename src/components/ideal_components/{TorqueGenerator.cpp => torque_generator.cpp} (97%) rename src/components/ideal_components/{TorqueGenerator.hpp => torque_generator.hpp} (93%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index d70bd78cc..d82761f96 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -42,7 +42,7 @@ add_library(${PROJECT_NAME} STATIC ideal_components/force_generator.cpp ideal_components/initialize_force_generator.cpp - ideal_components/TorqueGenerator.cpp + ideal_components/torque_generator.cpp ideal_components/initialize_torque_generator.cpp mission/Telescope.cpp diff --git a/src/components/ideal_components/initialize_torque_generator.hpp b/src/components/ideal_components/initialize_torque_generator.hpp index 9e0c1d796..5ce2bd365 100644 --- a/src/components/ideal_components/initialize_torque_generator.hpp +++ b/src/components/ideal_components/initialize_torque_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ -#include "TorqueGenerator.hpp" +#include "torque_generator.hpp" /** * @fn InitializeTorqueGenerator diff --git a/src/components/ideal_components/TorqueGenerator.cpp b/src/components/ideal_components/torque_generator.cpp similarity index 97% rename from src/components/ideal_components/TorqueGenerator.cpp rename to src/components/ideal_components/torque_generator.cpp index d7c987634..4e01c35c1 100644 --- a/src/components/ideal_components/TorqueGenerator.cpp +++ b/src/components/ideal_components/torque_generator.cpp @@ -1,9 +1,9 @@ /* - * @file TorqueGenerator.cpp + * @file torque_generator.cpp * @brief Ideal component which can generate torque for control algorithm test */ -#include "TorqueGenerator.hpp" +#include "torque_generator.hpp" #include diff --git a/src/components/ideal_components/TorqueGenerator.hpp b/src/components/ideal_components/torque_generator.hpp similarity index 93% rename from src/components/ideal_components/TorqueGenerator.hpp rename to src/components/ideal_components/torque_generator.hpp index bbf60365b..7f353e631 100644 --- a/src/components/ideal_components/TorqueGenerator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -1,15 +1,16 @@ /* - * @file TorqueGenerator.hpp + * @file torque_generator.hpp * @brief Ideal component which can generate torque for control algorithm test */ -#pragma once -#include -#include +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ #include #include +#include #include +#include /* * @class TorqueGenerator @@ -91,3 +92,5 @@ class TorqueGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; + +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ From efa9ca74c21bdbeac0251d28d91b03408833c102 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:19:19 +0100 Subject: [PATCH 0326/1086] Rename Telescope --- src/components/CMakeLists.txt | 4 ++-- .../{InitTelescope.cpp => initialize_telescope.cpp} | 4 ++-- .../{InitTelescope.hpp => initialize_telescope.hpp} | 10 +++++++--- .../mission/{Telescope.cpp => telescope.cpp} | 4 ++-- src/components/mission/{Telescope.h => telescope.hpp} | 11 +++++++---- 5 files changed, 20 insertions(+), 13 deletions(-) rename src/components/mission/{InitTelescope.cpp => initialize_telescope.cpp} (97%) rename src/components/mission/{InitTelescope.hpp => initialize_telescope.hpp} (72%) rename src/components/mission/{Telescope.cpp => telescope.cpp} (99%) rename src/components/mission/{Telescope.h => telescope.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index d82761f96..e5a518626 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -45,8 +45,8 @@ add_library(${PROJECT_NAME} STATIC ideal_components/torque_generator.cpp ideal_components/initialize_torque_generator.cpp - mission/Telescope.cpp - mission/InitTelescope.cpp + mission/telescope.cpp + mission/initialize_telescope.cpp power/PCU.cpp power/BAT.cpp diff --git a/src/components/mission/InitTelescope.cpp b/src/components/mission/initialize_telescope.cpp similarity index 97% rename from src/components/mission/InitTelescope.cpp rename to src/components/mission/initialize_telescope.cpp index 8e76caec1..b3617c024 100644 --- a/src/components/mission/InitTelescope.cpp +++ b/src/components/mission/initialize_telescope.cpp @@ -1,9 +1,9 @@ /* - * @file InitTelescope.cpp + * @file initialize_telescope.cpp * @brief Initialize function of Telescope */ -#include "InitTelescope.hpp" +#include "initialize_telescope.hpp" #include diff --git a/src/components/mission/InitTelescope.hpp b/src/components/mission/initialize_telescope.hpp similarity index 72% rename from src/components/mission/InitTelescope.hpp rename to src/components/mission/initialize_telescope.hpp index f2f578b7b..fa1584efc 100644 --- a/src/components/mission/InitTelescope.hpp +++ b/src/components/mission/initialize_telescope.hpp @@ -1,10 +1,12 @@ /* - * @file InitTelescope.hpp + * @file initialize_telescope.hpp * @brief Initialize function of Telescope */ -#pragma once -#include +#ifndef S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ +#define S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ + +#include /* * @fn InitTelescope @@ -18,3 +20,5 @@ */ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); + +#endif // S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ diff --git a/src/components/mission/Telescope.cpp b/src/components/mission/telescope.cpp similarity index 99% rename from src/components/mission/Telescope.cpp rename to src/components/mission/telescope.cpp index c100cd68d..a59384de6 100644 --- a/src/components/mission/Telescope.cpp +++ b/src/components/mission/telescope.cpp @@ -1,9 +1,9 @@ /* - * @file Telescope.cpp + * @file telescope.cpp * @brief Component emulation: Telescope */ -#include "Telescope.h" +#include "telescope.hpp" #include #include diff --git a/src/components/mission/Telescope.h b/src/components/mission/telescope.hpp similarity index 96% rename from src/components/mission/Telescope.h rename to src/components/mission/telescope.hpp index 4260d21be..5053ca3dd 100644 --- a/src/components/mission/Telescope.h +++ b/src/components/mission/telescope.hpp @@ -1,17 +1,18 @@ /* - * @file Telescope.h + * @file telescope.hpp * @brief Component emulation: Telescope */ -#pragma once -#include -#include +#ifndef S2E_COMPONENTS_MISSION_TELESCOPE_H_ +#define S2E_COMPONENTS_MISSION_TELESCOPE_H_ #include #include +#include #include #include #include +#include #include /* @@ -121,3 +122,5 @@ class Telescope : public ComponentBase, public ILoggable { // double angle_moon; //************************************************************* }; + +#endif // S2E_COMPONENTS_MISSION_TELESCOPE_H_ From 4067f2d0e753878f7b692f66bbdf345afaa8187f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:21:28 +0100 Subject: [PATCH 0327/1086] Rename BAT --- src/components/CMakeLists.txt | 2 +- src/components/power/InitBat.hpp | 2 +- src/components/power/PCU_InitialStudy.h | 2 +- src/components/power/{BAT.cpp => battery.cpp} | 4 ++-- src/components/power/{BAT.h => battery.hpp} | 9 ++++++--- 5 files changed, 11 insertions(+), 8 deletions(-) rename src/components/power/{BAT.cpp => battery.cpp} (98%) rename src/components/power/{BAT.h => battery.hpp} (97%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index e5a518626..901cd44fe 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -49,7 +49,7 @@ add_library(${PROJECT_NAME} STATIC mission/initialize_telescope.cpp power/PCU.cpp - power/BAT.cpp + power/battery.cpp power/InitBat.cpp power/PCU_InitialStudy.cpp power/InitPcu_InitialStudy.cpp diff --git a/src/components/power/InitBat.hpp b/src/components/power/InitBat.hpp index fddf1ce9d..df2eadcdf 100644 --- a/src/components/power/InitBat.hpp +++ b/src/components/power/InitBat.hpp @@ -4,7 +4,7 @@ */ #pragma once -#include +#include /* * @fn InitBAT diff --git a/src/components/power/PCU_InitialStudy.h b/src/components/power/PCU_InitialStudy.h index 7692e3fae..4ade1bbd1 100644 --- a/src/components/power/PCU_InitialStudy.h +++ b/src/components/power/PCU_InitialStudy.h @@ -9,7 +9,7 @@ #include #include "../base_classes/component_base.hpp" -#include "BAT.h" +#include "battery.hpp" #include "SAP.h" class PCU_InitialStudy : public ComponentBase, public ILoggable { diff --git a/src/components/power/BAT.cpp b/src/components/power/battery.cpp similarity index 98% rename from src/components/power/BAT.cpp rename to src/components/power/battery.cpp index 559b65440..5f345cadb 100644 --- a/src/components/power/BAT.cpp +++ b/src/components/power/battery.cpp @@ -1,9 +1,9 @@ /* - * @file BAT.cpp + * @file battery.cpp * @brief Component emulation of battery */ -#include "BAT.h" +#include "battery.hpp" #include diff --git a/src/components/power/BAT.h b/src/components/power/battery.hpp similarity index 97% rename from src/components/power/BAT.h rename to src/components/power/battery.hpp index a87637e20..9e60828d6 100644 --- a/src/components/power/BAT.h +++ b/src/components/power/battery.hpp @@ -1,11 +1,12 @@ /* - * @file BAT.h + * @file battery.hpp * @brief Component emulation of battery */ -#pragma once -#include +#ifndef S2E_COMPONENTS_POWER_BATTERY_H_ +#define S2E_COMPONENTS_POWER_BATTERY_H_ +#include #include #include "../base_classes/component_base.hpp" @@ -130,3 +131,5 @@ class BAT : public ComponentBase, public ILoggable { */ void UpdateBatVoltage(); }; + +#endif // S2E_COMPONENTS_POWER_BATTERY_H_ From c33b4766e31ae06562e10801f4a3576b91412276 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:23:45 +0100 Subject: [PATCH 0328/1086] Rename CsvScenarioInterface --- src/components/CMakeLists.txt | 2 +- src/components/power/PCU_InitialStudy.cpp | 2 +- src/components/power/SAP.cpp | 2 +- ...svScenarioInterface.cpp => csv_scenario_interface.cpp} | 4 ++-- ...{CsvScenarioInterface.h => csv_scenario_interface.hpp} | 8 ++++++-- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/components/power/{CsvScenarioInterface.cpp => csv_scenario_interface.cpp} (97%) rename src/components/power/{CsvScenarioInterface.h => csv_scenario_interface.hpp} (91%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 901cd44fe..af5d10ad7 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -55,7 +55,7 @@ add_library(${PROJECT_NAME} STATIC power/InitPcu_InitialStudy.cpp power/SAP.cpp power/InitSap.cpp - power/CsvScenarioInterface.cpp + power/csv_scenario_interface.cpp propulsion/SimpleThruster.cpp propulsion/InitSimpleThruster.cpp diff --git a/src/components/power/PCU_InitialStudy.cpp b/src/components/power/PCU_InitialStudy.cpp index b3ed28009..eda1067bd 100644 --- a/src/components/power/PCU_InitialStudy.cpp +++ b/src/components/power/PCU_InitialStudy.cpp @@ -5,7 +5,7 @@ #include "PCU_InitialStudy.h" -#include +#include #include #include diff --git a/src/components/power/SAP.cpp b/src/components/power/SAP.cpp index fe98019c9..f9e32a573 100644 --- a/src/components/power/SAP.cpp +++ b/src/components/power/SAP.cpp @@ -1,6 +1,6 @@ #include "SAP.h" -#include +#include #include diff --git a/src/components/power/CsvScenarioInterface.cpp b/src/components/power/csv_scenario_interface.cpp similarity index 97% rename from src/components/power/CsvScenarioInterface.cpp rename to src/components/power/csv_scenario_interface.cpp index bd4005202..8f898f78b 100644 --- a/src/components/power/CsvScenarioInterface.cpp +++ b/src/components/power/csv_scenario_interface.cpp @@ -1,9 +1,9 @@ /* - * @file CsvScenarioInterface.cpp + * @file csv_scenario_interface.cpp * @brief Interface to read power related scenario in CSV file */ -#include "CsvScenarioInterface.h" +#include "csv_scenario_interface.hpp" #include diff --git a/src/components/power/CsvScenarioInterface.h b/src/components/power/csv_scenario_interface.hpp similarity index 91% rename from src/components/power/CsvScenarioInterface.h rename to src/components/power/csv_scenario_interface.hpp index c2de451bb..e8a0b6c9d 100644 --- a/src/components/power/CsvScenarioInterface.h +++ b/src/components/power/csv_scenario_interface.hpp @@ -1,8 +1,10 @@ /* - * @file CsvScenarioInterface.h + * @file csv_scenario_interface.hpp * @brief Interface to read power related scenario in CSV file */ -#pragma once + +#ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ +#define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ #include #include @@ -75,3 +77,5 @@ class CsvScenarioInterface { static std::map buffer_line_id_; //!< Buffer line ID static std::map buffers_; //!< Buffer }; + +#endif // S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ From d03c53233c614288d1410332cb1e677377b66d5e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:26:06 +0100 Subject: [PATCH 0329/1086] Rename InitBAT --- src/components/CMakeLists.txt | 2 +- .../power/{InitBat.cpp => initialize_battery.cpp} | 4 ++-- .../power/{InitBat.hpp => initialize_battery.hpp} | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) rename src/components/power/{InitBat.cpp => initialize_battery.cpp} (96%) rename src/components/power/{InitBat.hpp => initialize_battery.hpp} (69%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index af5d10ad7..77b08d09f 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -50,7 +50,7 @@ add_library(${PROJECT_NAME} STATIC power/PCU.cpp power/battery.cpp - power/InitBat.cpp + power/initialize_battery.cpp power/PCU_InitialStudy.cpp power/InitPcu_InitialStudy.cpp power/SAP.cpp diff --git a/src/components/power/InitBat.cpp b/src/components/power/initialize_battery.cpp similarity index 96% rename from src/components/power/InitBat.cpp rename to src/components/power/initialize_battery.cpp index 5863ea506..360046bdb 100644 --- a/src/components/power/InitBat.cpp +++ b/src/components/power/initialize_battery.cpp @@ -1,9 +1,9 @@ /* - * @file InitBAT.cpp + * @file initialize_battery.cpp * @brief Initialize function of BAT */ #define _CRT_SECURE_NO_WARNINGS -#include "InitBat.hpp" +#include "initialize_battery.hpp" #include #include diff --git a/src/components/power/InitBat.hpp b/src/components/power/initialize_battery.hpp similarity index 69% rename from src/components/power/InitBat.hpp rename to src/components/power/initialize_battery.hpp index df2eadcdf..8ef11bff1 100644 --- a/src/components/power/InitBat.hpp +++ b/src/components/power/initialize_battery.hpp @@ -1,8 +1,10 @@ /* - * @file InitBAT.hpp + * @file initialize_battery.hpp * @brief Initialize function of BAT */ -#pragma once + +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ +#define S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ #include @@ -15,3 +17,5 @@ * @param [in] compo_step_time: Component step time [sec] */ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time); + +#endif // S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ From 746a5968b668852443a237cef9c2e81b94c52705 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:28:23 +0100 Subject: [PATCH 0330/1086] Rename InitPCU_InitialStudy --- src/components/CMakeLists.txt | 2 +- ..._InitialStudy.cpp => initialize_pcu_initial_study.cpp} | 4 ++-- ..._InitialStudy.hpp => initialize_pcu_initial_study.hpp} | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) rename src/components/power/{InitPcu_InitialStudy.cpp => initialize_pcu_initial_study.cpp} (90%) rename src/components/power/{InitPcu_InitialStudy.hpp => initialize_pcu_initial_study.hpp} (74%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 77b08d09f..34788a6be 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -52,7 +52,7 @@ add_library(${PROJECT_NAME} STATIC power/battery.cpp power/initialize_battery.cpp power/PCU_InitialStudy.cpp - power/InitPcu_InitialStudy.cpp + power/initialize_pcu_initial_study.cpp power/SAP.cpp power/InitSap.cpp power/csv_scenario_interface.cpp diff --git a/src/components/power/InitPcu_InitialStudy.cpp b/src/components/power/initialize_pcu_initial_study.cpp similarity index 90% rename from src/components/power/InitPcu_InitialStudy.cpp rename to src/components/power/initialize_pcu_initial_study.cpp index 6ad22ecb3..7660e81e3 100644 --- a/src/components/power/InitPcu_InitialStudy.cpp +++ b/src/components/power/initialize_pcu_initial_study.cpp @@ -1,10 +1,10 @@ /* - * @file InitPCU_InitialStudy.cpp + * @file initialize_pcu_initial_study.cpp * @brief Initialize function of PCU_InitialStudy */ #define _CRT_SECURE_NO_WARNINGS -#include "InitPcu_InitialStudy.hpp" +#include "initialize_pcu_initial_study.hpp" #include #include diff --git a/src/components/power/InitPcu_InitialStudy.hpp b/src/components/power/initialize_pcu_initial_study.hpp similarity index 74% rename from src/components/power/InitPcu_InitialStudy.hpp rename to src/components/power/initialize_pcu_initial_study.hpp index b0d55d483..695391cf4 100644 --- a/src/components/power/InitPcu_InitialStudy.hpp +++ b/src/components/power/initialize_pcu_initial_study.hpp @@ -1,8 +1,10 @@ /* - * @file InitPCU_InitialStudy.hpp + * @file initialize_pcu_initial_study.hpp * @brief Initialize function of PCU_InitialStudy */ -#pragma once + +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ +#define S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ #include @@ -18,3 +20,5 @@ */ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time); + +#endif // S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ From 7b1e7247075ef7f2e3165b1f9bb69de05c4a750d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:30:12 +0100 Subject: [PATCH 0331/1086] Rename InitSap --- src/components/CMakeLists.txt | 2 +- .../{InitSap.cpp => initialize_solar_array_paddle.cpp} | 4 ++-- .../{InitSap.hpp => initialize_solar_array_paddle.hpp} | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) rename src/components/power/{InitSap.cpp => initialize_solar_array_paddle.cpp} (96%) rename src/components/power/{InitSap.hpp => initialize_solar_array_paddle.hpp} (81%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 34788a6be..fff7b6ee7 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -54,7 +54,7 @@ add_library(${PROJECT_NAME} STATIC power/PCU_InitialStudy.cpp power/initialize_pcu_initial_study.cpp power/SAP.cpp - power/InitSap.cpp + power/initialize_solar_array_paddle.cpp power/csv_scenario_interface.cpp propulsion/SimpleThruster.cpp diff --git a/src/components/power/InitSap.cpp b/src/components/power/initialize_solar_array_paddle.cpp similarity index 96% rename from src/components/power/InitSap.cpp rename to src/components/power/initialize_solar_array_paddle.cpp index ac83d340b..feebc43b1 100644 --- a/src/components/power/InitSap.cpp +++ b/src/components/power/initialize_solar_array_paddle.cpp @@ -1,9 +1,9 @@ /* - * @file InitSap.cpp + * @file initialize_solar_array_paddle.cpp * @brief Initialize function of SAP (Solar Array Panel) */ #define _CRT_SECURE_NO_WARNINGS -#include "InitSap.hpp" +#include "initialize_solar_array_paddle.hpp" #include diff --git a/src/components/power/InitSap.hpp b/src/components/power/initialize_solar_array_paddle.hpp similarity index 81% rename from src/components/power/InitSap.hpp rename to src/components/power/initialize_solar_array_paddle.hpp index 117f26937..430dc168a 100644 --- a/src/components/power/InitSap.hpp +++ b/src/components/power/initialize_solar_array_paddle.hpp @@ -1,8 +1,10 @@ /* - * @file InitSap.hpp + * @file initialize_solar_array_paddle.hpp * @brief Initialize function of SAP (Solar Array Panel) */ -#pragma once + +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ +#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ #include @@ -29,3 +31,5 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons * @param [in] compo_step_time: Component step time [sec] */ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time); + +#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ From 70bcba6ed7f9a6c68e63427c0d0b2fb394a77db6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:32:03 +0100 Subject: [PATCH 0332/1086] Rename PCU_InitialStudy --- src/components/CMakeLists.txt | 2 +- src/components/power/initialize_pcu_initial_study.hpp | 2 +- .../{PCU_InitialStudy.cpp => pcu_initial_study.cpp} | 4 ++-- .../{PCU_InitialStudy.h => pcu_initial_study.hpp} | 11 +++++++---- 4 files changed, 11 insertions(+), 8 deletions(-) rename src/components/power/{PCU_InitialStudy.cpp => pcu_initial_study.cpp} (98%) rename src/components/power/{PCU_InitialStudy.h => pcu_initial_study.hpp} (92%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index fff7b6ee7..6ff000bc8 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -51,7 +51,7 @@ add_library(${PROJECT_NAME} STATIC power/PCU.cpp power/battery.cpp power/initialize_battery.cpp - power/PCU_InitialStudy.cpp + power/pcu_initial_study.cpp power/initialize_pcu_initial_study.cpp power/SAP.cpp power/initialize_solar_array_paddle.cpp diff --git a/src/components/power/initialize_pcu_initial_study.hpp b/src/components/power/initialize_pcu_initial_study.hpp index 695391cf4..7d99e6d94 100644 --- a/src/components/power/initialize_pcu_initial_study.hpp +++ b/src/components/power/initialize_pcu_initial_study.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ #define S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ -#include +#include /* * @fn InitPCU_InitialStudy diff --git a/src/components/power/PCU_InitialStudy.cpp b/src/components/power/pcu_initial_study.cpp similarity index 98% rename from src/components/power/PCU_InitialStudy.cpp rename to src/components/power/pcu_initial_study.cpp index eda1067bd..c01675fdb 100644 --- a/src/components/power/PCU_InitialStudy.cpp +++ b/src/components/power/pcu_initial_study.cpp @@ -1,9 +1,9 @@ /* - * @file PCU_InitialStudy.cpp + * @file pcu_initial_study.cpp * @brief Component emulation of Power Control Unit for initial study of spacecraft project */ -#include "PCU_InitialStudy.h" +#include "pcu_initial_study.hpp" #include diff --git a/src/components/power/PCU_InitialStudy.h b/src/components/power/pcu_initial_study.hpp similarity index 92% rename from src/components/power/PCU_InitialStudy.h rename to src/components/power/pcu_initial_study.hpp index 4ade1bbd1..94ef49922 100644 --- a/src/components/power/PCU_InitialStudy.h +++ b/src/components/power/pcu_initial_study.hpp @@ -1,16 +1,17 @@ /* - * @file PCU_InitialStudy.h + * @file pcu_initial_study.hpp * @brief Component emulation of Power Control Unit for initial study of spacecraft project */ -#pragma once -#include +#ifndef S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ +#define S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ +#include #include #include "../base_classes/component_base.hpp" -#include "battery.hpp" #include "SAP.h" +#include "battery.hpp" class PCU_InitialStudy : public ComponentBase, public ILoggable { public: @@ -79,3 +80,5 @@ class PCU_InitialStudy : public ComponentBase, public ILoggable { */ void UpdateChargeCurrentAndBusVoltage(); }; + +#endif // S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ From c70226dfcb307bbf8979f5d568c504488f354817 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:33:57 +0100 Subject: [PATCH 0333/1086] Rename PCU --- src/components/CMakeLists.txt | 2 +- src/components/power/{PCU.cpp => power_control_unit.cpp} | 4 ++-- src/components/power/{PCU.h => power_control_unit.hpp} | 9 ++++++--- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 4 files changed, 10 insertions(+), 7 deletions(-) rename src/components/power/{PCU.cpp => power_control_unit.cpp} (95%) rename src/components/power/{PCU.h => power_control_unit.hpp} (93%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 6ff000bc8..f65ec07aa 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -48,7 +48,7 @@ add_library(${PROJECT_NAME} STATIC mission/telescope.cpp mission/initialize_telescope.cpp - power/PCU.cpp + power/power_control_unit.cpp power/battery.cpp power/initialize_battery.cpp power/pcu_initial_study.cpp diff --git a/src/components/power/PCU.cpp b/src/components/power/power_control_unit.cpp similarity index 95% rename from src/components/power/PCU.cpp rename to src/components/power/power_control_unit.cpp index ec9f3cb27..320a8feb6 100644 --- a/src/components/power/PCU.cpp +++ b/src/components/power/power_control_unit.cpp @@ -1,8 +1,8 @@ /* - * @file PCU.cpp + * @file power_control_unit.cpp * @brief Component emulation of Power Control Unit */ -#include "PCU.h" +#include "power_control_unit.hpp" PCU::PCU(ClockGenerator* clock_gen) : ComponentBase(1, clock_gen) {} diff --git a/src/components/power/PCU.h b/src/components/power/power_control_unit.hpp similarity index 93% rename from src/components/power/PCU.h rename to src/components/power/power_control_unit.hpp index f12ec961c..a9d7aefae 100644 --- a/src/components/power/PCU.h +++ b/src/components/power/power_control_unit.hpp @@ -1,12 +1,13 @@ /* - * @file PCU.h + * @file power_control_unit.hpp * @brief Component emulation of Power Control Unit */ -#pragma once -#include +#ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ +#define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ #include +#include #include #include "../base_classes/component_base.hpp" @@ -92,3 +93,5 @@ class PCU : public ComponentBase, public ILoggable { private: std::map ports_; //!< Power port list }; + +#endif // S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index a34a20fff..3ed617117 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #include -#include +#include #include #include From b96e42fb5b38a4464c9390cc4b41504175283c86 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:36:15 +0100 Subject: [PATCH 0334/1086] Rename SAP --- src/components/CMakeLists.txt | 2 +- src/components/power/initialize_solar_array_paddle.hpp | 2 +- src/components/power/pcu_initial_study.hpp | 2 +- src/components/power/{SAP.cpp => solar_array_paddle.cpp} | 8 ++++++-- src/components/power/{SAP.h => solar_array_paddle.hpp} | 9 ++++++--- 5 files changed, 15 insertions(+), 8 deletions(-) rename src/components/power/{SAP.cpp => solar_array_paddle.cpp} (97%) rename src/components/power/{SAP.h => solar_array_paddle.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f65ec07aa..8ddc32244 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -53,7 +53,7 @@ add_library(${PROJECT_NAME} STATIC power/initialize_battery.cpp power/pcu_initial_study.cpp power/initialize_pcu_initial_study.cpp - power/SAP.cpp + power/solar_array_paddle.cpp power/initialize_solar_array_paddle.cpp power/csv_scenario_interface.cpp diff --git a/src/components/power/initialize_solar_array_paddle.hpp b/src/components/power/initialize_solar_array_paddle.hpp index 430dc168a..43ab75265 100644 --- a/src/components/power/initialize_solar_array_paddle.hpp +++ b/src/components/power/initialize_solar_array_paddle.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ #define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ -#include +#include /* * @fn InitSAP diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index 94ef49922..c54c6a059 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -10,8 +10,8 @@ #include #include "../base_classes/component_base.hpp" -#include "SAP.h" #include "battery.hpp" +#include "solar_array_paddle.hpp" class PCU_InitialStudy : public ComponentBase, public ILoggable { public: diff --git a/src/components/power/SAP.cpp b/src/components/power/solar_array_paddle.cpp similarity index 97% rename from src/components/power/SAP.cpp rename to src/components/power/solar_array_paddle.cpp index f9e32a573..15475d29b 100644 --- a/src/components/power/SAP.cpp +++ b/src/components/power/solar_array_paddle.cpp @@ -1,7 +1,11 @@ -#include "SAP.h" +/* + * @file solar_array_paddle.cpp + * @brief Component emulation of Solar Array Panel + */ -#include +#include "solar_array_paddle.hpp" +#include #include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, diff --git a/src/components/power/SAP.h b/src/components/power/solar_array_paddle.hpp similarity index 96% rename from src/components/power/SAP.h rename to src/components/power/solar_array_paddle.hpp index 99cd8ca31..2946c6323 100644 --- a/src/components/power/SAP.h +++ b/src/components/power/solar_array_paddle.hpp @@ -1,14 +1,15 @@ /* - * @file SAP.h + * @file solar_array_paddle.hpp * @brief Component emulation of Solar Array Panel */ -#pragma once -#include +#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ +#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ #include #include #include +#include #include "../base_classes/component_base.hpp" @@ -127,3 +128,5 @@ class SAP : public ComponentBase, public ILoggable { */ void MainRoutine(int time_count) override; }; + +#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ From 41866f9e566b7bb007b4d970ea5178e872675b59 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:39:34 +0100 Subject: [PATCH 0335/1086] Fix paddle to panel --- src/components/CMakeLists.txt | 4 ++-- ...ray_paddle.cpp => initialize_solar_array_panel.cpp} | 4 ++-- ...ray_paddle.hpp => initialize_solar_array_panel.hpp} | 10 +++++----- src/components/power/pcu_initial_study.hpp | 2 +- .../{solar_array_paddle.cpp => solar_array_panel.cpp} | 4 ++-- .../{solar_array_paddle.hpp => solar_array_panel.hpp} | 8 ++++---- 6 files changed, 16 insertions(+), 16 deletions(-) rename src/components/power/{initialize_solar_array_paddle.cpp => initialize_solar_array_panel.cpp} (96%) rename src/components/power/{initialize_solar_array_paddle.hpp => initialize_solar_array_panel.hpp} (78%) rename src/components/power/{solar_array_paddle.cpp => solar_array_panel.cpp} (98%) rename src/components/power/{solar_array_paddle.hpp => solar_array_panel.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 8ddc32244..39d419360 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -53,8 +53,8 @@ add_library(${PROJECT_NAME} STATIC power/initialize_battery.cpp power/pcu_initial_study.cpp power/initialize_pcu_initial_study.cpp - power/solar_array_paddle.cpp - power/initialize_solar_array_paddle.cpp + power/solar_array_panel.cpp + power/initialize_solar_array_panel.cpp power/csv_scenario_interface.cpp propulsion/SimpleThruster.cpp diff --git a/src/components/power/initialize_solar_array_paddle.cpp b/src/components/power/initialize_solar_array_panel.cpp similarity index 96% rename from src/components/power/initialize_solar_array_paddle.cpp rename to src/components/power/initialize_solar_array_panel.cpp index feebc43b1..dd9da7003 100644 --- a/src/components/power/initialize_solar_array_paddle.cpp +++ b/src/components/power/initialize_solar_array_panel.cpp @@ -1,9 +1,9 @@ /* - * @file initialize_solar_array_paddle.cpp + * @file initialize_solar_array_panel.cpp * @brief Initialize function of SAP (Solar Array Panel) */ #define _CRT_SECURE_NO_WARNINGS -#include "initialize_solar_array_paddle.hpp" +#include "initialize_solar_array_panel.hpp" #include diff --git a/src/components/power/initialize_solar_array_paddle.hpp b/src/components/power/initialize_solar_array_panel.hpp similarity index 78% rename from src/components/power/initialize_solar_array_paddle.hpp rename to src/components/power/initialize_solar_array_panel.hpp index 43ab75265..18cd702f7 100644 --- a/src/components/power/initialize_solar_array_paddle.hpp +++ b/src/components/power/initialize_solar_array_panel.hpp @@ -1,12 +1,12 @@ /* - * @file initialize_solar_array_paddle.hpp + * @file initialize_solar_array_panel.hpp * @brief Initialize function of SAP (Solar Array Panel) */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ -#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ +#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ -#include +#include /* * @fn InitSAP @@ -32,4 +32,4 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons */ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PADDLE_H_ +#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index c54c6a059..b971d0382 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -11,7 +11,7 @@ #include "../base_classes/component_base.hpp" #include "battery.hpp" -#include "solar_array_paddle.hpp" +#include "solar_array_panel.hpp" class PCU_InitialStudy : public ComponentBase, public ILoggable { public: diff --git a/src/components/power/solar_array_paddle.cpp b/src/components/power/solar_array_panel.cpp similarity index 98% rename from src/components/power/solar_array_paddle.cpp rename to src/components/power/solar_array_panel.cpp index 15475d29b..5d23115ea 100644 --- a/src/components/power/solar_array_paddle.cpp +++ b/src/components/power/solar_array_panel.cpp @@ -1,9 +1,9 @@ /* - * @file solar_array_paddle.cpp + * @file solar_array_panel.cpp * @brief Component emulation of Solar Array Panel */ -#include "solar_array_paddle.hpp" +#include "solar_array_panel.hpp" #include #include diff --git a/src/components/power/solar_array_paddle.hpp b/src/components/power/solar_array_panel.hpp similarity index 96% rename from src/components/power/solar_array_paddle.hpp rename to src/components/power/solar_array_panel.hpp index 2946c6323..01e62de53 100644 --- a/src/components/power/solar_array_paddle.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -1,10 +1,10 @@ /* - * @file solar_array_paddle.hpp + * @file solar_array_panel.hpp * @brief Component emulation of Solar Array Panel */ -#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ -#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ +#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ +#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ #include #include @@ -129,4 +129,4 @@ class SAP : public ComponentBase, public ILoggable { void MainRoutine(int time_count) override; }; -#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PADDLE_H_ +#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ From 16d07864e89b9b603419176ec8c7fe55875dc76b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 14:43:55 +0100 Subject: [PATCH 0336/1086] Rename simple thruster --- src/components/CMakeLists.txt | 4 ++-- ...pleThruster.cpp => initialize_simple_thruster.cpp} | 4 ++-- ...pleThruster.hpp => initialize_simple_thruster.hpp} | 10 +++++++--- .../{SimpleThruster.cpp => simple_thruster.cpp} | 4 ++-- .../{SimpleThruster.h => simple_thruster.hpp} | 11 +++++++---- .../sample_spacecraft/sample_components.hpp | 2 +- 6 files changed, 21 insertions(+), 14 deletions(-) rename src/components/propulsion/{InitSimpleThruster.cpp => initialize_simple_thruster.cpp} (96%) rename src/components/propulsion/{InitSimpleThruster.hpp => initialize_simple_thruster.hpp} (79%) rename src/components/propulsion/{SimpleThruster.cpp => simple_thruster.cpp} (98%) rename src/components/propulsion/{SimpleThruster.h => simple_thruster.hpp} (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 39d419360..ecf19b4f0 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -57,8 +57,8 @@ add_library(${PROJECT_NAME} STATIC power/initialize_solar_array_panel.cpp power/csv_scenario_interface.cpp - propulsion/SimpleThruster.cpp - propulsion/InitSimpleThruster.cpp + propulsion/simple_thruster.cpp + propulsion/initialize_simple_thruster.cpp ) diff --git a/src/components/propulsion/InitSimpleThruster.cpp b/src/components/propulsion/initialize_simple_thruster.cpp similarity index 96% rename from src/components/propulsion/InitSimpleThruster.cpp rename to src/components/propulsion/initialize_simple_thruster.cpp index b566c90c2..9f100a527 100644 --- a/src/components/propulsion/InitSimpleThruster.cpp +++ b/src/components/propulsion/initialize_simple_thruster.cpp @@ -1,8 +1,8 @@ /* - * @file InitSimpleThruster.cpp + * @file initialize_simple_thruster.cpp * @brief Initialize function os SimpleThruster */ -#include "InitSimpleThruster.hpp" +#include "initialize_simple_thruster.hpp" #include diff --git a/src/components/propulsion/InitSimpleThruster.hpp b/src/components/propulsion/initialize_simple_thruster.hpp similarity index 79% rename from src/components/propulsion/InitSimpleThruster.hpp rename to src/components/propulsion/initialize_simple_thruster.hpp index 4f47610f9..e2b4419aa 100644 --- a/src/components/propulsion/InitSimpleThruster.hpp +++ b/src/components/propulsion/initialize_simple_thruster.hpp @@ -1,10 +1,12 @@ /* - * @file InitSimpleThruster.hpp + * @file initialize_simple_thruster.hpp * @brief Initialize function os SimpleThruster */ -#pragma once -#include +#ifndef S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ +#define S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ + +#include /** * @fn InitSimpleThruster @@ -29,3 +31,5 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co */ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics); + +#endif // S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ diff --git a/src/components/propulsion/SimpleThruster.cpp b/src/components/propulsion/simple_thruster.cpp similarity index 98% rename from src/components/propulsion/SimpleThruster.cpp rename to src/components/propulsion/simple_thruster.cpp index 05b9f46cd..d677ce7a1 100644 --- a/src/components/propulsion/SimpleThruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -1,8 +1,8 @@ /* - * @file SimpleThruster.p + * @file simple_thruster.cpp * @brief Component emulation of simple thruster */ -#include "SimpleThruster.h" +#include "simple_thruster.hpp" #include diff --git a/src/components/propulsion/SimpleThruster.h b/src/components/propulsion/simple_thruster.hpp similarity index 96% rename from src/components/propulsion/SimpleThruster.h rename to src/components/propulsion/simple_thruster.hpp index f1ec785ef..1aad36e13 100644 --- a/src/components/propulsion/SimpleThruster.h +++ b/src/components/propulsion/simple_thruster.hpp @@ -1,15 +1,16 @@ /* - * @file SimpleThruster.h + * @file simple_thruster.hpp * @brief Component emulation of simple thruster */ -#pragma once -#include -#include +#ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ +#define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ #include #include #include +#include +#include #include #include "../base_classes/component_base.hpp" @@ -150,3 +151,5 @@ class SimpleThruster : public ComponentBase, public ILoggable { const Structure* structure_; //!< Spacecraft structure information const Dynamics* dynamics_; //!< Spacecraft dynamics information }; + +#endif // S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 3ed617117..76f11b63c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include #include #include From 4482bea67267ab0b0fa60abfa5d3e9f000ac8cff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:15:18 +0100 Subject: [PATCH 0337/1086] Fix format --- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/sun_sensor.cpp | 3 ++- .../examples/example_change_structure.hpp | 1 - src/components/power/pcu_initial_study.cpp | 3 +-- src/disturbances/air_drag.hpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 3 +-- src/dynamics/attitude/attitude_rk4.cpp | 3 +-- src/dynamics/attitude/controlled_attitude.cpp | 3 +-- src/dynamics/orbit/orbit.hpp | 3 +-- src/dynamics/thermal/initialize_node.cpp | 1 - src/dynamics/thermal/initialize_temperature.cpp | 3 +-- src/dynamics/thermal/node.hpp | 1 - src/dynamics/thermal/temperature.hpp | 1 - src/environment/global/celestial_information.cpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 3 +-- src/environment/global/clock_generator.hpp | 1 - src/environment/global/global_environment.hpp | 1 - src/environment/global/gnss_satellites.cpp | 2 +- src/environment/global/gnss_satellites.hpp | 3 +-- src/environment/global/hipparcos_catalogue.hpp | 3 +-- .../global/initialize_global_environment.cpp | 2 +- .../global/initialize_gnss_satellites.cpp | 1 - src/environment/global/simulation_time.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- .../local/initialize_local_environment.cpp | 1 - .../local/local_celestial_information.cpp | 2 +- src/environment/local/local_environment.cpp | 5 ++--- src/environment/local/local_environment.hpp | 1 - .../local/solar_radiation_pressure_environment.cpp | 3 +-- .../local/solar_radiation_pressure_environment.hpp | 3 +-- src/interface/hils/com_port_interface.hpp | 2 +- src/interface/sils/ports/power_port.cpp | 3 +-- src/simulation/case/simulation_case.hpp | 3 +-- src/simulation/ground_station/ground_station.cpp | 7 +++---- .../sample_ground_station/sample_ground_station.hpp | 3 +-- .../initialize_monte_carlo_simulation.cpp | 3 +-- src/simulation/spacecraft/installed_components.hpp | 3 +-- .../sample_spacecraft/sample_components.hpp | 13 ++++++------- .../spacecraft/structure/initialize_structure.cpp | 3 +-- src/simulation/spacecraft/structure/structure.cpp | 1 - 49 files changed, 48 insertions(+), 77 deletions(-) diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 7c95f9147..6cc721dc2 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -5,11 +5,11 @@ #include "magnetorquer.hpp" -#include #include #include #include +#include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 010af3511..1339f232e 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -5,12 +5,12 @@ #include "star_sensor.hpp" -#include #include #include #include #include +#include #include using namespace std; diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index 9f075ce95..2b4098d80 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -8,9 +8,10 @@ #include #include using libra::NormalRand; -#include #include +#include + using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 3ceb38f67..148f30604 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -6,7 +6,6 @@ #pragma once #include - #include #include "../base_classes/component_base.hpp" diff --git a/src/components/power/pcu_initial_study.cpp b/src/components/power/pcu_initial_study.cpp index c01675fdb..fc4d4fa91 100644 --- a/src/components/power/pcu_initial_study.cpp +++ b/src/components/power/pcu_initial_study.cpp @@ -5,9 +5,8 @@ #include "pcu_initial_study.hpp" -#include - #include +#include #include PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 36d27e2f2..8f0c54730 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,10 +9,10 @@ #include #include -#include "../interface/log_output/loggable.hpp" #include "../Library/math/Quaternion.hpp" #include "../Library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" +#include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 9f38386df..e65f43b69 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,10 +8,10 @@ #include -#include "../interface/log_output/loggable.hpp" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" using libra::Matrix; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 236906996..2ca1ecb14 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,10 +8,10 @@ #include -#include "../interface/log_output/loggable.hpp" #include "../Library/math/MatVec.hpp" #include "../Library/math/Matrix.hpp" #include "../Library/math/Vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "simple_disturbance.hpp" using libra::Matrix; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index e162c2ec8..156929593 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,9 +9,9 @@ using libra::NormalRand; #include -#include "../interface/log_output/log_utility.hpp" #include "../Library/math/GlobalRand.h" #include "../Library/math/RandomWalk.hpp" +#include "../interface/log_output/log_utility.hpp" using namespace std; diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index c4acdd156..aa8e8d86d 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,8 +9,8 @@ #include #include -#include "../interface/log_output/loggable.hpp" #include "../Library/math/Vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 8d9fe2763..c95a48ad3 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,8 +10,8 @@ #include #include -#include "../interface/log_output/loggable.hpp" #include "../Library/math/Vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" /** diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index e08710dd5..6048de17b 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,10 +6,9 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include - #include #include +#include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index cebc69da2..9b117c263 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,9 +4,8 @@ */ #include "attitude_rk4.hpp" -#include - #include +#include using namespace std; #include diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 796074fc3..d94ba55cc 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,10 +4,9 @@ */ #include "controlled_attitude.hpp" -#include - #include #include +#include using namespace std; diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index edf94a3a5..fc1ab3b62 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,11 +16,10 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include - #include #include #include +#include /** * @enum OrbitPropagateMode diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index 395a0e5b9..465f731f8 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -6,7 +6,6 @@ #include "initialize_node.hpp" #include - #include #include #include diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 6ec978304..90ef6a15f 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -5,9 +5,8 @@ #include "initialize_temperature.hpp" -#include - #include +#include #include #include "initialize_node.hpp" diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index 70105b56a..0c9b9a431 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -7,7 +7,6 @@ #define S2E_DYNAMICS_THERMAL_NODE_H_ #include - #include #include diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 2d9b10e32..1f27adc98 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -7,7 +7,6 @@ #define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ #include - #include #include diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 0f96e05a0..b46ccfd37 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -6,11 +6,11 @@ #include "celestial_information.hpp" -#include #include #include #include +#include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 1553f3b72..8842e6913 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,12 +10,12 @@ #include #include -#include "interface/log_output/loggable.hpp" #include "Library/math/MatVec.hpp" #include "Library/math/Matrix.hpp" #include "Library/math/Quaternion.hpp" #include "Library/math/Vector.hpp" #include "celestial_rotation.hpp" +#include "interface/log_output/loggable.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 95c3518bd..ff77643af 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,13 +10,12 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include - #include #include #include #include #include +#include #include using libra::Quaternion; diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index d83aa347a..34d964367 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -7,7 +7,6 @@ #define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ #include - #include #include "simulation_time.hpp" diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 1ca3d2098..c3fe1a2b9 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -7,7 +7,6 @@ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ #include - #include #include "celestial_information.hpp" diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index cc3959849..a02462f62 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,7 +5,6 @@ #include "gnss_satellites.hpp" -#include #include //for jday() #include //for gstime() @@ -13,6 +12,7 @@ #include #include #include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 4ebfed84a..300fe7dc6 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,12 +6,11 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include - #include #include #include #include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 5db97e510..cb45c4cd8 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,10 +6,9 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include - #include #include +#include #include /** diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 7d3b9fd9c..23713400c 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -4,11 +4,11 @@ */ #include "initialize_global_environment.hpp" -#include #include #include #include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index dbea9fd3c..5ebf81f06 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -6,7 +6,6 @@ #include "initialize_gnss_satellites.hpp" #include - #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index df099a6aa..6ca040b8f 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,12 +12,12 @@ #include // #include -#include #include #include #include #include +#include /** *@struct TimeState diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 866243f18..6c2aad1f2 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,12 +5,12 @@ #include "atmosphere.hpp" -#include #include #include #include #include +#include using libra::NormalRand; using libra::Vector; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index a8a4e5465..ce55be30d 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,11 +7,11 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include #include #include #include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 8453a41c4..fba19761d 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,12 +5,12 @@ #include "geomagnetic_field.hpp" -#include #include #include #include #include +#include using libra::NormalRand; using namespace std; diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 1d73ac665..e9a0f646f 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -6,7 +6,6 @@ #include "initialize_local_environment.hpp" #include - #include #define CALC_LABEL "calculation" diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index f9d0e90c7..8a1789728 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -5,10 +5,10 @@ #include "local_celestial_information.hpp" -#include #include #include +#include #include #include diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index b69953c0d..6bc90238e 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,10 +4,9 @@ */ #include "local_environment.hpp" -#include -#include - #include +#include +#include #include "initialize_local_environment.hpp" diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index da46eb8bd..38fdb1eef 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -7,7 +7,6 @@ #define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ #include - #include #include "atmosphere.hpp" diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 18d2cc398..da856c598 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,14 +4,13 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include - #include #include #include #include #include #include +#include using libra::Vector; using namespace std; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 13cd47d2d..b866e3237 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,10 +6,9 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include - #include #include +#include using libra::Vector; diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index 386023ef1..3f9bf937e 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -8,10 +8,10 @@ #ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ #define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ -#include #include #include +#include #include using namespace System; diff --git a/src/interface/sils/ports/power_port.cpp b/src/interface/sils/ports/power_port.cpp index 223c264f6..d3246c81a 100644 --- a/src/interface/sils/ports/power_port.cpp +++ b/src/interface/sils/ports/power_port.cpp @@ -5,9 +5,8 @@ #include "power_port.hpp" -#include - #include +#include PowerPort::PowerPort() : kPortId(-1), current_limit_(10.0), minimum_voltage_(3.3), assumed_power_consumption_(0.0) { is_on_ = true; // power on to work the component diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index c55888f03..919146c0f 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -6,9 +6,8 @@ #ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ #define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#include - #include +#include #include #include "../simulation_configuration.hpp" diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index ed04de391..acf215a84 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,13 +5,12 @@ #include "ground_station.hpp" -#include -#include -#include - #include #include #include +#include +#include +#include #include GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id) { diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index c047f524c..b2c7a1fe3 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -6,9 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ -#include - #include +#include #include #include diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index c7dcb7ce5..c774813a0 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -5,9 +5,8 @@ #include "initialize_monte_carlo_simulation.hpp" -#include - #include +#include #define MAX_CHAR_NUM 256 diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index e6b88294c..c0f04bf8a 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,9 +6,8 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include - #include +#include /** * @class InstalledComponents diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 76f11b63c..dc224361b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,14 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include -#include - #include -#include -#include -#include -#include #include #include #include @@ -21,10 +14,16 @@ #include #include #include +#include +#include #include #include #include #include +#include +#include +#include +#include #include #include #include diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index ffd481668..174e62066 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,9 +5,8 @@ #include "initialize_structure.hpp" -#include - #include +#include #define MIN_VAL 1e-6 KinematicsParams InitKinematicsParams(std::string ini_path) { diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 15beb5c57..b953fb912 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -6,7 +6,6 @@ #include "structure.hpp" #include - #include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } From 6442132139a2a13767dc4093ebb3a44d5e875b7c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:18:57 +0100 Subject: [PATCH 0338/1086] Rename Library directory --- CMakeLists.txt | 22 +++++++++---------- .../sample_local_environment.ini | 2 +- src/components/aocs/gnss_receiver.cpp | 2 +- src/components/aocs/gnss_receiver.hpp | 4 ++-- src/components/aocs/gyro_sensor.hpp | 2 +- .../aocs/initialize_star_sensor.cpp | 2 +- src/components/aocs/initialize_sun_sensor.cpp | 2 +- src/components/aocs/magnetometer.cpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/aocs/magnetorquer.cpp | 6 ++--- src/components/aocs/magnetorquer.hpp | 10 ++++----- src/components/aocs/reaction_wheel.cpp | 4 ++-- src/components/aocs/reaction_wheel.hpp | 2 +- src/components/aocs/reaction_wheel_jitter.cpp | 2 +- src/components/aocs/reaction_wheel_jitter.hpp | 4 ++-- src/components/aocs/reaction_wheel_ode.cpp | 2 +- src/components/aocs/reaction_wheel_ode.hpp | 4 ++-- src/components/aocs/star_sensor.cpp | 6 ++--- src/components/aocs/star_sensor.hpp | 8 +++---- src/components/aocs/sun_sensor.cpp | 6 ++--- src/components/aocs/sun_sensor.hpp | 6 ++--- .../base_classes/component_base.hpp | 2 +- src/components/base_classes/sensor_base.hpp | 8 +++---- .../base_classes/sensor_base_tfs.hpp | 2 +- src/components/communication/antenna.cpp | 2 +- src/components/communication/antenna.hpp | 4 ++-- .../antenna_radiation_pattern.cpp | 2 +- .../antenna_radiation_pattern.hpp | 2 +- .../ground_station_calculator.cpp | 2 +- .../ground_station_calculator.hpp | 6 ++--- .../communication/initialize_antenna.cpp | 2 +- .../example_serial_communication_for_hils.cpp | 2 +- .../ideal_components/force_generator.hpp | 4 ++-- .../ideal_components/torque_generator.hpp | 4 ++-- .../mission/initialize_telescope.cpp | 2 +- src/components/mission/telescope.cpp | 2 +- src/components/mission/telescope.hpp | 4 ++-- .../power/csv_scenario_interface.hpp | 2 +- src/components/power/solar_array_panel.hpp | 2 +- .../propulsion/initialize_simple_thruster.cpp | 2 +- src/components/propulsion/simple_thruster.cpp | 4 ++-- src/components/propulsion/simple_thruster.hpp | 6 ++--- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 4 ++-- src/disturbances/disturbance.hpp | 2 +- src/disturbances/geopotential.hpp | 6 ++--- src/disturbances/gravity_gradient.hpp | 6 ++--- src/disturbances/magnetic_disturbance.cpp | 8 +++---- src/disturbances/magnetic_disturbance.hpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 4 ++-- src/disturbances/surface_force.cpp | 2 +- src/disturbances/surface_force.hpp | 4 ++-- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 4 ++-- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 4 ++-- src/dynamics/dynamics.hpp | 2 +- .../orbit/encke_orbit_propagation.cpp | 4 ++-- .../orbit/encke_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/initialize_orbit.hpp | 2 +- .../orbit/kepler_orbit_propagation.cpp | 4 ++-- .../orbit/kepler_orbit_propagation.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 12 +++++----- src/dynamics/orbit/relative_orbit.cpp | 2 +- src/dynamics/orbit/relative_orbit.hpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 4 ++-- src/dynamics/thermal/temperature.cpp | 2 +- .../global/celestial_information.hpp | 8 +++---- src/environment/global/celestial_rotation.cpp | 6 ++--- src/environment/global/celestial_rotation.hpp | 8 +++---- src/environment/global/gnss_satellites.cpp | 8 +++---- src/environment/global/gnss_satellites.hpp | 2 +- .../global/hipparcos_catalogue.cpp | 2 +- .../global/hipparcos_catalogue.hpp | 4 ++-- src/environment/global/simulation_time.hpp | 6 ++--- src/environment/local/atmosphere.cpp | 8 +++---- src/environment/local/atmosphere.hpp | 6 ++--- src/environment/local/geomagnetic_field.cpp | 8 +++---- src/environment/local/geomagnetic_field.hpp | 4 ++-- .../solar_radiation_pressure_environment.cpp | 4 ++-- .../solar_radiation_pressure_environment.hpp | 2 +- src/interface/hils/hils_port_manager.cpp | 2 +- .../initialize/initialize_file_access.hpp | 6 ++--- src/interface/log_output/log_utility.hpp | 4 ++-- src/interface/sils/ports/i2c_port.cpp | 2 +- .../Geodesy/CMakeLists.txt | 0 .../Geodesy/GeodeticPosition.cpp | 6 ++--- .../Geodesy/GeodeticPosition.hpp | 4 ++-- src/{Library => library}/Orbit/CMakeLists.txt | 0 .../Orbit/KeplerOrbit.cpp | 0 src/{Library => library}/Orbit/KeplerOrbit.h | 0 .../Orbit/OrbitalElements.cpp | 0 .../Orbit/OrbitalElements.h | 0 .../RelativeOrbit/CMakeLists.txt | 0 .../RelativeOrbit/RelativeOrbitModels.cpp | 0 .../RelativeOrbit/RelativeOrbitModels.h | 0 src/{Library => library}/igrf/CMakeLists.txt | 0 src/{Library => library}/igrf/igrf.cpp | 12 +++++----- src/{Library => library}/igrf/igrf.h | 0 src/{Library => library}/igrf/igrf11.coef | 0 src/{Library => library}/igrf/igrf12.coef | 0 src/{Library => library}/igrf/igrf13.coef | 0 src/{Library => library}/inih/CMakeLists.txt | 0 src/{Library => library}/inih/LICENSE.txt | 0 src/{Library => library}/inih/README.md | 0 .../inih/cpp/INIReader.cpp | 0 src/{Library => library}/inih/cpp/INIReader.h | 0 src/{Library => library}/inih/ini.c | 0 src/{Library => library}/inih/ini.h | 0 src/{Library => library}/math/CMakeLists.txt | 0 src/{Library => library}/math/Constant.hpp | 0 src/{Library => library}/math/GlobalRand.cpp | 0 src/{Library => library}/math/GlobalRand.h | 0 src/{Library => library}/math/MatVec.hpp | 0 src/{Library => library}/math/MatVec_impl.hpp | 0 src/{Library => library}/math/Matrix.hpp | 0 src/{Library => library}/math/Matrix_ifs.hpp | 0 src/{Library => library}/math/Matrix_tfs.hpp | 0 src/{Library => library}/math/NormalRand.cpp | 0 src/{Library => library}/math/NormalRand.hpp | 0 .../math/NormalRand_ifs.hpp | 0 src/{Library => library}/math/ODE.hpp | 0 src/{Library => library}/math/ODE_ifs.hpp | 0 src/{Library => library}/math/ODE_impl.hpp | 0 src/{Library => library}/math/ODE_tfs.hpp | 0 .../math/Quantization.cpp | 0 src/{Library => library}/math/Quantization.h | 0 src/{Library => library}/math/Quaternion.cpp | 0 src/{Library => library}/math/Quaternion.hpp | 0 .../math/Quaternion_ifs.hpp | 0 src/{Library => library}/math/Ran0.cpp | 0 src/{Library => library}/math/Ran0.hpp | 0 src/{Library => library}/math/Ran1.cpp | 0 src/{Library => library}/math/Ran1.hpp | 0 src/{Library => library}/math/RandomWalk.hpp | 0 .../math/RandomWalk_tfs.hpp | 4 ++-- .../math/TestQuaternion.cpp | 0 src/{Library => library}/math/Vector.cpp | 0 src/{Library => library}/math/Vector.hpp | 0 src/{Library => library}/math/Vector_ifs.hpp | 0 src/{Library => library}/math/Vector_tfs.hpp | 0 src/{Library => library}/math/s2e_math.cpp | 2 +- src/{Library => library}/math/s2e_math.hpp | 0 .../nrlmsise00/CMakeLists.txt | 0 .../nrlmsise00/Wrapper_nrlmsise00.cpp | 4 ++-- .../nrlmsise00/Wrapper_nrlmsise00.h | 2 +- .../optics/CMakeLists.txt | 0 .../optics/GaussianBeamBase.cpp | 2 +- .../optics/GaussianBeamBase.h | 0 src/{Library => library}/sgp4/CMakeLists.txt | 0 src/{Library => library}/sgp4/sgp4ext.cpp | 0 src/{Library => library}/sgp4/sgp4ext.h | 0 src/{Library => library}/sgp4/sgp4io.cpp | 0 src/{Library => library}/sgp4/sgp4io.h | 0 src/{Library => library}/sgp4/sgp4unit.cpp | 2 +- src/{Library => library}/sgp4/sgp4unit.h | 0 src/{Library => library}/utils/CMakeLists.txt | 0 .../utils/ENDIAN_DEFINE.h | 0 src/{Library => library}/utils/Macros.hpp | 0 src/{Library => library}/utils/endian.cpp | 0 src/{Library => library}/utils/endian.h | 0 src/{Library => library}/utils/slip.cpp | 0 src/{Library => library}/utils/slip.h | 0 .../ground_station/ground_station.cpp | 4 ++-- .../ground_station/ground_station.hpp | 4 ++-- .../inter_spacecraft_communication.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 2 +- .../initialize_monte_carlo_parameters.hpp | 4 ++-- .../monte_carlo_simulation_executor.hpp | 2 +- .../simulation_object.hpp | 4 ++-- .../spacecraft/installed_components.cpp | 2 +- .../spacecraft/installed_components.hpp | 2 +- .../sample_spacecraft/sample_components.hpp | 2 +- .../sample_spacecraft/sample_spacecraft.cpp | 2 +- .../structure/initialize_structure.cpp | 2 +- .../structure/kinematics_parameters.hpp | 4 ++-- .../structure/residual_magnetic_moment.hpp | 2 +- .../spacecraft/structure/surface.hpp | 2 +- 181 files changed, 217 insertions(+), 217 deletions(-) rename src/{Library => library}/Geodesy/CMakeLists.txt (100%) rename src/{Library => library}/Geodesy/GeodeticPosition.cpp (95%) rename src/{Library => library}/Geodesy/GeodeticPosition.hpp (96%) rename src/{Library => library}/Orbit/CMakeLists.txt (100%) rename src/{Library => library}/Orbit/KeplerOrbit.cpp (100%) rename src/{Library => library}/Orbit/KeplerOrbit.h (100%) rename src/{Library => library}/Orbit/OrbitalElements.cpp (100%) rename src/{Library => library}/Orbit/OrbitalElements.h (100%) rename src/{Library => library}/RelativeOrbit/CMakeLists.txt (100%) rename src/{Library => library}/RelativeOrbit/RelativeOrbitModels.cpp (100%) rename src/{Library => library}/RelativeOrbit/RelativeOrbitModels.h (100%) rename src/{Library => library}/igrf/CMakeLists.txt (100%) rename src/{Library => library}/igrf/igrf.cpp (97%) rename src/{Library => library}/igrf/igrf.h (100%) rename src/{Library => library}/igrf/igrf11.coef (100%) rename src/{Library => library}/igrf/igrf12.coef (100%) rename src/{Library => library}/igrf/igrf13.coef (100%) rename src/{Library => library}/inih/CMakeLists.txt (100%) rename src/{Library => library}/inih/LICENSE.txt (100%) rename src/{Library => library}/inih/README.md (100%) rename src/{Library => library}/inih/cpp/INIReader.cpp (100%) rename src/{Library => library}/inih/cpp/INIReader.h (100%) rename src/{Library => library}/inih/ini.c (100%) rename src/{Library => library}/inih/ini.h (100%) rename src/{Library => library}/math/CMakeLists.txt (100%) rename src/{Library => library}/math/Constant.hpp (100%) rename src/{Library => library}/math/GlobalRand.cpp (100%) rename src/{Library => library}/math/GlobalRand.h (100%) rename src/{Library => library}/math/MatVec.hpp (100%) rename src/{Library => library}/math/MatVec_impl.hpp (100%) rename src/{Library => library}/math/Matrix.hpp (100%) rename src/{Library => library}/math/Matrix_ifs.hpp (100%) rename src/{Library => library}/math/Matrix_tfs.hpp (100%) rename src/{Library => library}/math/NormalRand.cpp (100%) rename src/{Library => library}/math/NormalRand.hpp (100%) rename src/{Library => library}/math/NormalRand_ifs.hpp (100%) rename src/{Library => library}/math/ODE.hpp (100%) rename src/{Library => library}/math/ODE_ifs.hpp (100%) rename src/{Library => library}/math/ODE_impl.hpp (100%) rename src/{Library => library}/math/ODE_tfs.hpp (100%) rename src/{Library => library}/math/Quantization.cpp (100%) rename src/{Library => library}/math/Quantization.h (100%) rename src/{Library => library}/math/Quaternion.cpp (100%) rename src/{Library => library}/math/Quaternion.hpp (100%) rename src/{Library => library}/math/Quaternion_ifs.hpp (100%) rename src/{Library => library}/math/Ran0.cpp (100%) rename src/{Library => library}/math/Ran0.hpp (100%) rename src/{Library => library}/math/Ran1.cpp (100%) rename src/{Library => library}/math/Ran1.hpp (100%) rename src/{Library => library}/math/RandomWalk.hpp (100%) rename src/{Library => library}/math/RandomWalk_tfs.hpp (91%) rename src/{Library => library}/math/TestQuaternion.cpp (100%) rename src/{Library => library}/math/Vector.cpp (100%) rename src/{Library => library}/math/Vector.hpp (100%) rename src/{Library => library}/math/Vector_ifs.hpp (100%) rename src/{Library => library}/math/Vector_tfs.hpp (100%) rename src/{Library => library}/math/s2e_math.cpp (92%) rename src/{Library => library}/math/s2e_math.hpp (100%) rename src/{Library => library}/nrlmsise00/CMakeLists.txt (100%) rename src/{Library => library}/nrlmsise00/Wrapper_nrlmsise00.cpp (99%) rename src/{Library => library}/nrlmsise00/Wrapper_nrlmsise00.h (99%) rename src/{Library => library}/optics/CMakeLists.txt (100%) rename src/{Library => library}/optics/GaussianBeamBase.cpp (98%) rename src/{Library => library}/optics/GaussianBeamBase.h (100%) rename src/{Library => library}/sgp4/CMakeLists.txt (100%) rename src/{Library => library}/sgp4/sgp4ext.cpp (100%) rename src/{Library => library}/sgp4/sgp4ext.h (100%) rename src/{Library => library}/sgp4/sgp4io.cpp (100%) rename src/{Library => library}/sgp4/sgp4io.h (100%) rename src/{Library => library}/sgp4/sgp4unit.cpp (99%) rename src/{Library => library}/sgp4/sgp4unit.h (100%) rename src/{Library => library}/utils/CMakeLists.txt (100%) rename src/{Library => library}/utils/ENDIAN_DEFINE.h (100%) rename src/{Library => library}/utils/Macros.hpp (100%) rename src/{Library => library}/utils/endian.cpp (100%) rename src/{Library => library}/utils/endian.h (100%) rename src/{Library => library}/utils/slip.cpp (100%) rename src/{Library => library}/utils/slip.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2fa2686af..53c79ece4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,16 +74,16 @@ add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/log_output) add_subdirectory(src/interface/sils) add_subdirectory(src/interface/hils) -add_subdirectory(src/Library/igrf) -add_subdirectory(src/Library/inih) -add_subdirectory(src/Library/math) -add_subdirectory(src/Library/nrlmsise00) -add_subdirectory(src/Library/sgp4) -add_subdirectory(src/Library/utils) -add_subdirectory(src/Library/optics) -add_subdirectory(src/Library/RelativeOrbit) -add_subdirectory(src/Library/Orbit) -add_subdirectory(src/Library/Geodesy) +add_subdirectory(src/library/igrf) +add_subdirectory(src/library/inih) +add_subdirectory(src/library/math) +add_subdirectory(src/library/nrlmsise00) +add_subdirectory(src/library/sgp4) +add_subdirectory(src/library/utils) +add_subdirectory(src/library/optics) +add_subdirectory(src/library/RelativeOrbit) +add_subdirectory(src/library/Orbit) +add_subdirectory(src/library/Geodesy) set(SOURCE_FILES src/s2e.cpp @@ -212,7 +212,7 @@ if(GOOGLE_TEST) # Unit test set(TEST_PROJECT_NAME ${PROJECT_NAME}_TEST) set(TEST_FILES - src/Library/math/TestQuaternion.cpp + src/library/math/TestQuaternion.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/data/sample/initialize_files/sample_local_environment.ini b/data/sample/initialize_files/sample_local_environment.ini index 1371d73c8..2f4829223 100644 --- a/data/sample/initialize_files/sample_local_environment.ini +++ b/data/sample/initialize_files/sample_local_environment.ini @@ -1,7 +1,7 @@ [MAGNETIC_FIELD_ENVIRONMENT] calculation = ENABLE logging = ENABLE -coefficient_file = ../../../s2e-core/src/Library/igrf/igrf13.coef +coefficient_file = ../../../s2e-core/src/library/igrf/igrf13.coef magnetic_field_random_walk_speed_nT = 10.0 magnetic_field_random_walk_limit_nT = 400.0 magnetic_field_white_noise_standard_deviation_nT = 50.0 diff --git a/src/components/aocs/gnss_receiver.cpp b/src/components/aocs/gnss_receiver.cpp index 0977156ce..0bcfe476b 100644 --- a/src/components/aocs/gnss_receiver.cpp +++ b/src/components/aocs/gnss_receiver.cpp @@ -5,7 +5,7 @@ #include "gnss_receiver.hpp" -#include +#include #include #include diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 2bd50df5f..acaa14603 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ #define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index f4a6cb1b9..bdce733bc 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ #define S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ -#include +#include #include #include diff --git a/src/components/aocs/initialize_star_sensor.cpp b/src/components/aocs/initialize_star_sensor.cpp index a87b1734f..0c0b911ac 100644 --- a/src/components/aocs/initialize_star_sensor.cpp +++ b/src/components/aocs/initialize_star_sensor.cpp @@ -4,7 +4,7 @@ */ #include "initialize_star_sensor.hpp" -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/initialize_sun_sensor.cpp b/src/components/aocs/initialize_sun_sensor.cpp index fe486687d..bba6df4f5 100644 --- a/src/components/aocs/initialize_sun_sensor.cpp +++ b/src/components/aocs/initialize_sun_sensor.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/magnetometer.cpp b/src/components/aocs/magnetometer.cpp index cf8cbcfbb..ecee8e731 100644 --- a/src/components/aocs/magnetometer.cpp +++ b/src/components/aocs/magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "magnetometer.hpp" -#include +#include MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const MagEnvironment* magnet) diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 65fd60af0..56c7f908d 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ #define S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ -#include +#include #include #include diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 6cc721dc2..0b8f69998 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -5,10 +5,10 @@ #include "magnetorquer.hpp" -#include +#include -#include -#include +#include +#include #include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 15b913539..4d3c8237a 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -6,11 +6,11 @@ #ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ #define S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/src/components/aocs/reaction_wheel.cpp b/src/components/aocs/reaction_wheel.cpp index 0b09e7fad..ad0d262e6 100644 --- a/src/components/aocs/reaction_wheel.cpp +++ b/src/components/aocs/reaction_wheel.cpp @@ -4,8 +4,8 @@ */ #include "reaction_wheel.hpp" -#include -#include +#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index e5cef37ae..6dab0d807 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel_jitter.cpp b/src/components/aocs/reaction_wheel_jitter.cpp index cfa5cd0dd..5a2bcced7 100644 --- a/src/components/aocs/reaction_wheel_jitter.cpp +++ b/src/components/aocs/reaction_wheel_jitter.cpp @@ -5,7 +5,7 @@ #include "reaction_wheel_jitter.hpp" -#include +#include #include RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, diff --git a/src/components/aocs/reaction_wheel_jitter.hpp b/src/components/aocs/reaction_wheel_jitter.hpp index 3b3fd79e0..fc8fbf499 100644 --- a/src/components/aocs/reaction_wheel_jitter.hpp +++ b/src/components/aocs/reaction_wheel_jitter.hpp @@ -7,8 +7,8 @@ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ #pragma once -#include -#include +#include +#include #include /* diff --git a/src/components/aocs/reaction_wheel_ode.cpp b/src/components/aocs/reaction_wheel_ode.cpp index 6ea13a6b1..83f450c33 100644 --- a/src/components/aocs/reaction_wheel_ode.cpp +++ b/src/components/aocs/reaction_wheel_ode.cpp @@ -4,7 +4,7 @@ */ #include "reaction_wheel_ode.hpp" -#include +#include using namespace libra; diff --git a/src/components/aocs/reaction_wheel_ode.hpp b/src/components/aocs/reaction_wheel_ode.hpp index 6492813cb..1ba573640 100644 --- a/src/components/aocs/reaction_wheel_ode.hpp +++ b/src/components/aocs/reaction_wheel_ode.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ -#include -#include +#include +#include #include /* diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 1339f232e..eb0963476 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -5,10 +5,10 @@ #include "star_sensor.hpp" -#include +#include -#include -#include +#include +#include #include #include #include diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 5b0864084..75f9313dd 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -6,10 +6,10 @@ #ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ #define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index 2b4098d80..4a4b01361 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -5,10 +5,10 @@ #include "sun_sensor.hpp" -#include -#include +#include +#include using libra::NormalRand; -#include +#include #include diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index f474cac67..18785c170 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -6,9 +6,9 @@ #ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ #define S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index fea9c561d..19deb65f5 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ -#include +#include #include #include diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index 0e2631a2f..d1b9d14f8 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -6,10 +6,10 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ -#include -#include -#include -#include +#include +#include +#include +#include /** * @class SensorBase diff --git a/src/components/base_classes/sensor_base_tfs.hpp b/src/components/base_classes/sensor_base_tfs.hpp index 574cb3bf6..960dfe487 100644 --- a/src/components/base_classes/sensor_base_tfs.hpp +++ b/src/components/base_classes/sensor_base_tfs.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ #define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ -#include +#include template SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, diff --git a/src/components/communication/antenna.cpp b/src/components/communication/antenna.cpp index 0e24cea43..cae68cadf 100644 --- a/src/components/communication/antenna.cpp +++ b/src/components/communication/antenna.cpp @@ -5,7 +5,7 @@ #include "antenna.hpp" -#include +#include #include Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, diff --git a/src/components/communication/antenna.hpp b/src/components/communication/antenna.hpp index 33fd19507..a0cae1720 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ #define S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ -#include -#include +#include +#include using libra::Quaternion; using libra::Vector; #include diff --git a/src/components/communication/antenna_radiation_pattern.cpp b/src/components/communication/antenna_radiation_pattern.cpp index 6da080c2d..abe805f84 100644 --- a/src/components/communication/antenna_radiation_pattern.cpp +++ b/src/components/communication/antenna_radiation_pattern.cpp @@ -5,7 +5,7 @@ #include "antenna_radiation_pattern.hpp" -#include +#include #include #include diff --git a/src/components/communication/antenna_radiation_pattern.hpp b/src/components/communication/antenna_radiation_pattern.hpp index 697c877cf..597922380 100644 --- a/src/components/communication/antenna_radiation_pattern.hpp +++ b/src/components/communication/antenna_radiation_pattern.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ #define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ -#include +#include #include #include diff --git a/src/components/communication/ground_station_calculator.cpp b/src/components/communication/ground_station_calculator.cpp index df178a72a..c32acc07e 100644 --- a/src/components/communication/ground_station_calculator.cpp +++ b/src/components/communication/ground_station_calculator.cpp @@ -5,7 +5,7 @@ #include "ground_station_calculator.hpp" -#include +#include #include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index d50cc6373..c6664e915 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -7,9 +7,9 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ #define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/src/components/communication/initialize_antenna.cpp b/src/components/communication/initialize_antenna.cpp index 9d2cb17b8..dad2bedce 100644 --- a/src/components/communication/initialize_antenna.cpp +++ b/src/components/communication/initialize_antenna.cpp @@ -8,7 +8,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index 644008aa2..f3e47bee6 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -4,7 +4,7 @@ */ #include "example_serial_communication_for_hils.hpp" -#include +#include ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index e753dd9f0..3d5875c82 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 7f353e631..5cf925442 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/components/mission/initialize_telescope.cpp b/src/components/mission/initialize_telescope.cpp index b3617c024..cb6228414 100644 --- a/src/components/mission/initialize_telescope.cpp +++ b/src/components/mission/initialize_telescope.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/mission/telescope.cpp b/src/components/mission/telescope.cpp index a59384de6..077d0fb5b 100644 --- a/src/components/mission/telescope.cpp +++ b/src/components/mission/telescope.cpp @@ -5,7 +5,7 @@ #include "telescope.hpp" -#include +#include #include using namespace std; diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 5053ca3dd..9289133c1 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_MISSION_TELESCOPE_H_ #define S2E_COMPONENTS_MISSION_TELESCOPE_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/components/power/csv_scenario_interface.hpp b/src/components/power/csv_scenario_interface.hpp index e8a0b6c9d..116714a6a 100644 --- a/src/components/power/csv_scenario_interface.hpp +++ b/src/components/power/csv_scenario_interface.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ #define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ -#include +#include #include #include #include diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index 01e62de53..28de48605 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ #define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ -#include +#include #include #include #include diff --git a/src/components/propulsion/initialize_simple_thruster.cpp b/src/components/propulsion/initialize_simple_thruster.cpp index 9f100a527..41beaaae2 100644 --- a/src/components/propulsion/initialize_simple_thruster.cpp +++ b/src/components/propulsion/initialize_simple_thruster.cpp @@ -4,7 +4,7 @@ */ #include "initialize_simple_thruster.hpp" -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/propulsion/simple_thruster.cpp index d677ce7a1..aaefc93c2 100644 --- a/src/components/propulsion/simple_thruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -4,9 +4,9 @@ */ #include "simple_thruster.hpp" -#include +#include -#include +#include #include // Constructor diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 1aad36e13..2d9a1e062 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -6,9 +6,9 @@ #ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ #define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ -#include -#include -#include +#include +#include +#include #include #include #include diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index a90a45a61..d236b6f73 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,7 +5,7 @@ #include "air_drag.hpp" -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 8f0c54730..17ff15ea6 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,8 +9,8 @@ #include #include -#include "../Library/math/Quaternion.hpp" -#include "../Library/math/Vector.hpp" +#include "../library/math/Quaternion.hpp" +#include "../library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" #include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index f7d009c77..01ffe8596 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_DISTURBANCE_H_ #define S2E_DISTURBANCES_DISTURBANCE_H_ -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" using libra::Vector; /** diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index e65f43b69..f145de03a 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,9 +8,9 @@ #include -#include "../Library/math/MatVec.hpp" -#include "../Library/math/Matrix.hpp" -#include "../Library/math/Vector.hpp" +#include "../library/math/MatVec.hpp" +#include "../library/math/Matrix.hpp" +#include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 2ca1ecb14..481445cad 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,9 +8,9 @@ #include -#include "../Library/math/MatVec.hpp" -#include "../Library/math/Matrix.hpp" -#include "../Library/math/Vector.hpp" +#include "../library/math/MatVec.hpp" +#include "../library/math/Matrix.hpp" +#include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 156929593..d1a606a20 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -5,12 +5,12 @@ #include "magnetic_disturbance.hpp" -#include "../Library/math/NormalRand.hpp" +#include "../library/math/NormalRand.hpp" using libra::NormalRand; -#include +#include -#include "../Library/math/GlobalRand.h" -#include "../Library/math/RandomWalk.hpp" +#include "../library/math/GlobalRand.h" +#include "../library/math/RandomWalk.hpp" #include "../interface/log_output/log_utility.hpp" using namespace std; diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index ed9a093a6..bc81bb609 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -8,7 +8,7 @@ #include -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" using libra::Vector; #include "../interface/log_output/loggable.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index aa8e8d86d..bf9fb1e26 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -6,10 +6,10 @@ #ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ #define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ -#include +#include #include -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 2268f1fd5..5e6e5ea79 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -5,7 +5,7 @@ #include "surface_force.hpp" -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 2c13dae45..27166227a 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -8,8 +8,8 @@ #ifndef S2E_DISTURBANCES_SURFACE_FORCE_H_ #define S2E_DISTURBANCES_SURFACE_FORCE_H_ -#include "../Library/math/Quaternion.hpp" -#include "../Library/math/Vector.hpp" +#include "../library/math/Quaternion.hpp" +#include "../library/math/Vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" #include "simple_disturbance.hpp" using libra::Quaternion; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index c95a48ad3..1d789490c 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 6048de17b..d4c6c7ce8 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 9b117c263..8a7a660a4 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index d94ba55cc..e3e032741 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,8 +4,8 @@ */ #include "controlled_attitude.hpp" -#include -#include +#include +#include #include using namespace std; diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 21c16352d..e647211f9 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -7,7 +7,7 @@ #include -#include "../Library/math/Vector.hpp" +#include "../library/math/Vector.hpp" using libra::Vector; #include diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 1fce730bd..1afb60aff 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -5,9 +5,9 @@ #include "encke_orbit_propagation.hpp" -#include +#include -#include "../../Library/Orbit/OrbitalElements.h" +#include "../../library/Orbit/OrbitalElements.h" EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celes_info, const double mu_m3_s2, const double prop_step_s, const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 90fc7b4fa..d857026f7 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ -#include "../../Library/Orbit/KeplerOrbit.h" -#include "../../Library/math/ODE.hpp" +#include "../../library/Orbit/KeplerOrbit.h" +#include "../../library/math/ODE.hpp" #include "orbit.hpp" /** diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index b08d2fca2..ce9800346 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ -#include +#include #include "orbit.hpp" diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index c3c4e213b..230d4d75a 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -4,9 +4,9 @@ */ #include "kepler_orbit_propagation.hpp" -#include +#include -#include "../../Library/math/s2e_math.hpp" +#include "../../library/math/s2e_math.hpp" KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celes_info, const double current_jd, KeplerOrbit kepler_orbit) : Orbit(celes_info), KeplerOrbit(kepler_orbit) { diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index 95b64aa1a..c923b1a3b 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ -#include "../../Library/Orbit/KeplerOrbit.h" +#include "../../library/Orbit/KeplerOrbit.h" #include "orbit.hpp" /** diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index fc1ab3b62..a04145fab 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -6,17 +6,17 @@ #ifndef S2E_DYNAMICS_ORBIT_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_ORBIT_H_ -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include #include diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 49c771dd2..6b3448d09 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -4,7 +4,7 @@ */ #include "relative_orbit.hpp" -#include +#include #include "rk4_orbit_propagation.hpp" diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 032011580..48db2cf1a 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -6,9 +6,9 @@ #ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ -#include +#include -#include +#include #include #include diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 451d85421..455bcbf5b 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -4,7 +4,7 @@ */ #include "rk4_orbit_propagation.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 0dbfcf22b..512885906 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ -#include +#include #include #include "orbit.hpp" diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 2dbc985ea..be4ae5246 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -5,7 +5,7 @@ #include "sgp4_orbit_propagation.hpp" -#include +#include #include #include using namespace std; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 7b9e8ea51..aa6c29463 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ -#include -#include +#include +#include #include diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index a809ae508..c241c193e 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -5,7 +5,7 @@ #include "temperature.hpp" -#include +#include #include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 8842e6913..5e4be35f3 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,10 +10,10 @@ #include #include -#include "Library/math/MatVec.hpp" -#include "Library/math/Matrix.hpp" -#include "Library/math/Quaternion.hpp" -#include "Library/math/Vector.hpp" +#include "library/math/MatVec.hpp" +#include "library/math/Matrix.hpp" +#include "library/math/Quaternion.hpp" +#include "library/math/Vector.hpp" #include "celestial_rotation.hpp" #include "interface/log_output/loggable.hpp" diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 1fec2b871..68da09770 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -9,10 +9,10 @@ #include "celestial_rotation.hpp" -#include // for jday() -#include // for gstime() +#include // for jday() +#include // for gstime() -#include +#include #include #include diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index ff77643af..4058db893 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,10 +10,10 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include -#include -#include -#include +#include +#include +#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index a02462f62..447e51dd5 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,11 +5,11 @@ #include "gnss_satellites.hpp" -#include //for jday() -#include //for gstime() +#include //for jday() +#include //for gstime() -#include -#include +#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 300fe7dc6..46097be62 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index c146cf32c..beeb17daf 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -4,7 +4,7 @@ */ #include "hipparcos_catalogue.hpp" -#include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index cb45c4cd8..f36c81825 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,8 +6,8 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include -#include +#include +#include #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 6ca040b8f..32c73ff9d 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,9 +12,9 @@ #include // #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 6c2aad1f2..ea3b6464b 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,11 +5,11 @@ #include "atmosphere.hpp" -#include +#include -#include -#include -#include +#include +#include +#include #include using libra::NormalRand; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index ce55be30d..7c3a44fc8 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,10 +7,10 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include +#include -#include -#include +#include +#include #include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index fba19761d..b927a6998 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,11 +5,11 @@ #include "geomagnetic_field.hpp" -#include -#include +#include +#include -#include -#include +#include +#include #include using libra::NormalRand; diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 3c7bbb96c..cc4420f50 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -6,9 +6,9 @@ #ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ #define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ -#include +#include using libra::Vector; -#include +#include using libra::Quaternion; #include diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index da856c598..c0baa604a 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,8 +4,8 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include -#include +#include +#include #include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index b866e3237..295ab005c 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/interface/hils/hils_port_manager.cpp b/src/interface/hils/hils_port_manager.cpp index 2dba84e60..210235bfa 100644 --- a/src/interface/hils/hils_port_manager.cpp +++ b/src/interface/hils/hils_port_manager.cpp @@ -5,7 +5,7 @@ #include "hils_port_manager.hpp" -#include +#include // #define HILS_PORT_MANAGER_SHOW_DEBUG_DATA diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index 2e6860568..20666f50a 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -13,10 +13,10 @@ #include #include #else -#include +#include #endif -#include -#include +#include +#include #include #include #include diff --git a/src/interface/log_output/log_utility.hpp b/src/interface/log_output/log_utility.hpp index e83fb9dca..95e6d3a82 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/interface/log_output/log_utility.hpp @@ -6,8 +6,8 @@ #ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ #define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/interface/sils/ports/i2c_port.cpp b/src/interface/sils/ports/i2c_port.cpp index af072f4b1..acb532ae9 100644 --- a/src/interface/sils/ports/i2c_port.cpp +++ b/src/interface/sils/ports/i2c_port.cpp @@ -5,7 +5,7 @@ #include "i2c_port.hpp" -#include +#include I2CPort::I2CPort(void) {} diff --git a/src/Library/Geodesy/CMakeLists.txt b/src/library/Geodesy/CMakeLists.txt similarity index 100% rename from src/Library/Geodesy/CMakeLists.txt rename to src/library/Geodesy/CMakeLists.txt diff --git a/src/Library/Geodesy/GeodeticPosition.cpp b/src/library/Geodesy/GeodeticPosition.cpp similarity index 95% rename from src/Library/Geodesy/GeodeticPosition.cpp rename to src/library/Geodesy/GeodeticPosition.cpp index eef4c08fe..1f29e2fbd 100644 --- a/src/Library/Geodesy/GeodeticPosition.cpp +++ b/src/library/Geodesy/GeodeticPosition.cpp @@ -4,10 +4,10 @@ */ #include "GeodeticPosition.hpp" -#include // TODO: do not to use the functions in SGP4 library +#include // TODO: do not to use the functions in SGP4 library -#include -#include +#include +#include #include GeodeticPosition::GeodeticPosition() { diff --git a/src/Library/Geodesy/GeodeticPosition.hpp b/src/library/Geodesy/GeodeticPosition.hpp similarity index 96% rename from src/Library/Geodesy/GeodeticPosition.hpp rename to src/library/Geodesy/GeodeticPosition.hpp index 0202f2272..3417247ca 100644 --- a/src/Library/Geodesy/GeodeticPosition.hpp +++ b/src/library/Geodesy/GeodeticPosition.hpp @@ -4,8 +4,8 @@ */ #pragma once -#include -#include +#include +#include /** * @class GeodeticPosition diff --git a/src/Library/Orbit/CMakeLists.txt b/src/library/Orbit/CMakeLists.txt similarity index 100% rename from src/Library/Orbit/CMakeLists.txt rename to src/library/Orbit/CMakeLists.txt diff --git a/src/Library/Orbit/KeplerOrbit.cpp b/src/library/Orbit/KeplerOrbit.cpp similarity index 100% rename from src/Library/Orbit/KeplerOrbit.cpp rename to src/library/Orbit/KeplerOrbit.cpp diff --git a/src/Library/Orbit/KeplerOrbit.h b/src/library/Orbit/KeplerOrbit.h similarity index 100% rename from src/Library/Orbit/KeplerOrbit.h rename to src/library/Orbit/KeplerOrbit.h diff --git a/src/Library/Orbit/OrbitalElements.cpp b/src/library/Orbit/OrbitalElements.cpp similarity index 100% rename from src/Library/Orbit/OrbitalElements.cpp rename to src/library/Orbit/OrbitalElements.cpp diff --git a/src/Library/Orbit/OrbitalElements.h b/src/library/Orbit/OrbitalElements.h similarity index 100% rename from src/Library/Orbit/OrbitalElements.h rename to src/library/Orbit/OrbitalElements.h diff --git a/src/Library/RelativeOrbit/CMakeLists.txt b/src/library/RelativeOrbit/CMakeLists.txt similarity index 100% rename from src/Library/RelativeOrbit/CMakeLists.txt rename to src/library/RelativeOrbit/CMakeLists.txt diff --git a/src/Library/RelativeOrbit/RelativeOrbitModels.cpp b/src/library/RelativeOrbit/RelativeOrbitModels.cpp similarity index 100% rename from src/Library/RelativeOrbit/RelativeOrbitModels.cpp rename to src/library/RelativeOrbit/RelativeOrbitModels.cpp diff --git a/src/Library/RelativeOrbit/RelativeOrbitModels.h b/src/library/RelativeOrbit/RelativeOrbitModels.h similarity index 100% rename from src/Library/RelativeOrbit/RelativeOrbitModels.h rename to src/library/RelativeOrbit/RelativeOrbitModels.h diff --git a/src/Library/igrf/CMakeLists.txt b/src/library/igrf/CMakeLists.txt similarity index 100% rename from src/Library/igrf/CMakeLists.txt rename to src/library/igrf/CMakeLists.txt diff --git a/src/Library/igrf/igrf.cpp b/src/library/igrf/igrf.cpp similarity index 97% rename from src/Library/igrf/igrf.cpp rename to src/library/igrf/igrf.cpp index 1441d58ba..9f2468eda 100644 --- a/src/Library/igrf/igrf.cpp +++ b/src/library/igrf/igrf.cpp @@ -297,12 +297,12 @@ void gigrf(int gen, double year) { // char file[]="igrf10.coef"; // char path[] = "igrf11.coef"; // char file[] = "igrf11.coef"; - // char path[] = "src/Library/igrf/igrf11.coef"; - // char file[] = "src/Library/igrf/igrf11.coef"; - // char path[] = "../SatAttSim/src/Library/igrf/igrf12.coef"; - // char file[] = "../SatAttSim/src/Library/igrf/igrf12.coef"; - // char path[] = "../../SatAttSim/src/Library/igrf/igrf13.coef"; //from 2020 - // char file[] = "../../SatAttSim/src/Library/igrf/igrf13.coef"; //from 2020 + // char path[] = "src/library/igrf/igrf11.coef"; + // char file[] = "src/library/igrf/igrf11.coef"; + // char path[] = "../SatAttSim/src/library/igrf/igrf12.coef"; + // char file[] = "../SatAttSim/src/library/igrf/igrf12.coef"; + // char path[] = "../../SatAttSim/src/library/igrf/igrf13.coef"; //from 2020 + // char file[] = "../../SatAttSim/src/library/igrf/igrf13.coef"; //from 2020 char file[256]; diff --git a/src/Library/igrf/igrf.h b/src/library/igrf/igrf.h similarity index 100% rename from src/Library/igrf/igrf.h rename to src/library/igrf/igrf.h diff --git a/src/Library/igrf/igrf11.coef b/src/library/igrf/igrf11.coef similarity index 100% rename from src/Library/igrf/igrf11.coef rename to src/library/igrf/igrf11.coef diff --git a/src/Library/igrf/igrf12.coef b/src/library/igrf/igrf12.coef similarity index 100% rename from src/Library/igrf/igrf12.coef rename to src/library/igrf/igrf12.coef diff --git a/src/Library/igrf/igrf13.coef b/src/library/igrf/igrf13.coef similarity index 100% rename from src/Library/igrf/igrf13.coef rename to src/library/igrf/igrf13.coef diff --git a/src/Library/inih/CMakeLists.txt b/src/library/inih/CMakeLists.txt similarity index 100% rename from src/Library/inih/CMakeLists.txt rename to src/library/inih/CMakeLists.txt diff --git a/src/Library/inih/LICENSE.txt b/src/library/inih/LICENSE.txt similarity index 100% rename from src/Library/inih/LICENSE.txt rename to src/library/inih/LICENSE.txt diff --git a/src/Library/inih/README.md b/src/library/inih/README.md similarity index 100% rename from src/Library/inih/README.md rename to src/library/inih/README.md diff --git a/src/Library/inih/cpp/INIReader.cpp b/src/library/inih/cpp/INIReader.cpp similarity index 100% rename from src/Library/inih/cpp/INIReader.cpp rename to src/library/inih/cpp/INIReader.cpp diff --git a/src/Library/inih/cpp/INIReader.h b/src/library/inih/cpp/INIReader.h similarity index 100% rename from src/Library/inih/cpp/INIReader.h rename to src/library/inih/cpp/INIReader.h diff --git a/src/Library/inih/ini.c b/src/library/inih/ini.c similarity index 100% rename from src/Library/inih/ini.c rename to src/library/inih/ini.c diff --git a/src/Library/inih/ini.h b/src/library/inih/ini.h similarity index 100% rename from src/Library/inih/ini.h rename to src/library/inih/ini.h diff --git a/src/Library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt similarity index 100% rename from src/Library/math/CMakeLists.txt rename to src/library/math/CMakeLists.txt diff --git a/src/Library/math/Constant.hpp b/src/library/math/Constant.hpp similarity index 100% rename from src/Library/math/Constant.hpp rename to src/library/math/Constant.hpp diff --git a/src/Library/math/GlobalRand.cpp b/src/library/math/GlobalRand.cpp similarity index 100% rename from src/Library/math/GlobalRand.cpp rename to src/library/math/GlobalRand.cpp diff --git a/src/Library/math/GlobalRand.h b/src/library/math/GlobalRand.h similarity index 100% rename from src/Library/math/GlobalRand.h rename to src/library/math/GlobalRand.h diff --git a/src/Library/math/MatVec.hpp b/src/library/math/MatVec.hpp similarity index 100% rename from src/Library/math/MatVec.hpp rename to src/library/math/MatVec.hpp diff --git a/src/Library/math/MatVec_impl.hpp b/src/library/math/MatVec_impl.hpp similarity index 100% rename from src/Library/math/MatVec_impl.hpp rename to src/library/math/MatVec_impl.hpp diff --git a/src/Library/math/Matrix.hpp b/src/library/math/Matrix.hpp similarity index 100% rename from src/Library/math/Matrix.hpp rename to src/library/math/Matrix.hpp diff --git a/src/Library/math/Matrix_ifs.hpp b/src/library/math/Matrix_ifs.hpp similarity index 100% rename from src/Library/math/Matrix_ifs.hpp rename to src/library/math/Matrix_ifs.hpp diff --git a/src/Library/math/Matrix_tfs.hpp b/src/library/math/Matrix_tfs.hpp similarity index 100% rename from src/Library/math/Matrix_tfs.hpp rename to src/library/math/Matrix_tfs.hpp diff --git a/src/Library/math/NormalRand.cpp b/src/library/math/NormalRand.cpp similarity index 100% rename from src/Library/math/NormalRand.cpp rename to src/library/math/NormalRand.cpp diff --git a/src/Library/math/NormalRand.hpp b/src/library/math/NormalRand.hpp similarity index 100% rename from src/Library/math/NormalRand.hpp rename to src/library/math/NormalRand.hpp diff --git a/src/Library/math/NormalRand_ifs.hpp b/src/library/math/NormalRand_ifs.hpp similarity index 100% rename from src/Library/math/NormalRand_ifs.hpp rename to src/library/math/NormalRand_ifs.hpp diff --git a/src/Library/math/ODE.hpp b/src/library/math/ODE.hpp similarity index 100% rename from src/Library/math/ODE.hpp rename to src/library/math/ODE.hpp diff --git a/src/Library/math/ODE_ifs.hpp b/src/library/math/ODE_ifs.hpp similarity index 100% rename from src/Library/math/ODE_ifs.hpp rename to src/library/math/ODE_ifs.hpp diff --git a/src/Library/math/ODE_impl.hpp b/src/library/math/ODE_impl.hpp similarity index 100% rename from src/Library/math/ODE_impl.hpp rename to src/library/math/ODE_impl.hpp diff --git a/src/Library/math/ODE_tfs.hpp b/src/library/math/ODE_tfs.hpp similarity index 100% rename from src/Library/math/ODE_tfs.hpp rename to src/library/math/ODE_tfs.hpp diff --git a/src/Library/math/Quantization.cpp b/src/library/math/Quantization.cpp similarity index 100% rename from src/Library/math/Quantization.cpp rename to src/library/math/Quantization.cpp diff --git a/src/Library/math/Quantization.h b/src/library/math/Quantization.h similarity index 100% rename from src/Library/math/Quantization.h rename to src/library/math/Quantization.h diff --git a/src/Library/math/Quaternion.cpp b/src/library/math/Quaternion.cpp similarity index 100% rename from src/Library/math/Quaternion.cpp rename to src/library/math/Quaternion.cpp diff --git a/src/Library/math/Quaternion.hpp b/src/library/math/Quaternion.hpp similarity index 100% rename from src/Library/math/Quaternion.hpp rename to src/library/math/Quaternion.hpp diff --git a/src/Library/math/Quaternion_ifs.hpp b/src/library/math/Quaternion_ifs.hpp similarity index 100% rename from src/Library/math/Quaternion_ifs.hpp rename to src/library/math/Quaternion_ifs.hpp diff --git a/src/Library/math/Ran0.cpp b/src/library/math/Ran0.cpp similarity index 100% rename from src/Library/math/Ran0.cpp rename to src/library/math/Ran0.cpp diff --git a/src/Library/math/Ran0.hpp b/src/library/math/Ran0.hpp similarity index 100% rename from src/Library/math/Ran0.hpp rename to src/library/math/Ran0.hpp diff --git a/src/Library/math/Ran1.cpp b/src/library/math/Ran1.cpp similarity index 100% rename from src/Library/math/Ran1.cpp rename to src/library/math/Ran1.cpp diff --git a/src/Library/math/Ran1.hpp b/src/library/math/Ran1.hpp similarity index 100% rename from src/Library/math/Ran1.hpp rename to src/library/math/Ran1.hpp diff --git a/src/Library/math/RandomWalk.hpp b/src/library/math/RandomWalk.hpp similarity index 100% rename from src/Library/math/RandomWalk.hpp rename to src/library/math/RandomWalk.hpp diff --git a/src/Library/math/RandomWalk_tfs.hpp b/src/library/math/RandomWalk_tfs.hpp similarity index 91% rename from src/Library/math/RandomWalk_tfs.hpp rename to src/library/math/RandomWalk_tfs.hpp index c08281a68..9a726809b 100644 --- a/src/Library/math/RandomWalk_tfs.hpp +++ b/src/library/math/RandomWalk_tfs.hpp @@ -5,9 +5,9 @@ #pragma once -#include +#include -#include +#include template RandomWalk::RandomWalk(double step_width, const libra::Vector& stddev, const libra::Vector& limit) diff --git a/src/Library/math/TestQuaternion.cpp b/src/library/math/TestQuaternion.cpp similarity index 100% rename from src/Library/math/TestQuaternion.cpp rename to src/library/math/TestQuaternion.cpp diff --git a/src/Library/math/Vector.cpp b/src/library/math/Vector.cpp similarity index 100% rename from src/Library/math/Vector.cpp rename to src/library/math/Vector.cpp diff --git a/src/Library/math/Vector.hpp b/src/library/math/Vector.hpp similarity index 100% rename from src/Library/math/Vector.hpp rename to src/library/math/Vector.hpp diff --git a/src/Library/math/Vector_ifs.hpp b/src/library/math/Vector_ifs.hpp similarity index 100% rename from src/Library/math/Vector_ifs.hpp rename to src/library/math/Vector_ifs.hpp diff --git a/src/Library/math/Vector_tfs.hpp b/src/library/math/Vector_tfs.hpp similarity index 100% rename from src/Library/math/Vector_tfs.hpp rename to src/library/math/Vector_tfs.hpp diff --git a/src/Library/math/s2e_math.cpp b/src/library/math/s2e_math.cpp similarity index 92% rename from src/Library/math/s2e_math.cpp rename to src/library/math/s2e_math.cpp index 5cf6e1a0a..472ba4520 100644 --- a/src/Library/math/s2e_math.cpp +++ b/src/library/math/s2e_math.cpp @@ -5,7 +5,7 @@ #include "s2e_math.hpp" -#include +#include namespace libra { double WrapTo2Pi(const double angle) { diff --git a/src/Library/math/s2e_math.hpp b/src/library/math/s2e_math.hpp similarity index 100% rename from src/Library/math/s2e_math.hpp rename to src/library/math/s2e_math.hpp diff --git a/src/Library/nrlmsise00/CMakeLists.txt b/src/library/nrlmsise00/CMakeLists.txt similarity index 100% rename from src/Library/nrlmsise00/CMakeLists.txt rename to src/library/nrlmsise00/CMakeLists.txt diff --git a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp b/src/library/nrlmsise00/Wrapper_nrlmsise00.cpp similarity index 99% rename from src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp rename to src/library/nrlmsise00/Wrapper_nrlmsise00.cpp index 111a5ca7c..f95ad59b7 100644 --- a/src/Library/nrlmsise00/Wrapper_nrlmsise00.cpp +++ b/src/library/nrlmsise00/Wrapper_nrlmsise00.cpp @@ -1,6 +1,6 @@ /** * @file Wrapper_nrlmsise00.cpp - * @brief Functions to wrap NRLMSISE-00 air density model in the ExternalLibrary + * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ /* ------------------------------------------------------------------- */ @@ -12,7 +12,7 @@ extern "C" { } #include /* for malloc/free */ -#include +#include #include #include #include /* maths functions */ diff --git a/src/Library/nrlmsise00/Wrapper_nrlmsise00.h b/src/library/nrlmsise00/Wrapper_nrlmsise00.h similarity index 99% rename from src/Library/nrlmsise00/Wrapper_nrlmsise00.h rename to src/library/nrlmsise00/Wrapper_nrlmsise00.h index e3731f849..c66bfb559 100644 --- a/src/Library/nrlmsise00/Wrapper_nrlmsise00.h +++ b/src/library/nrlmsise00/Wrapper_nrlmsise00.h @@ -1,6 +1,6 @@ /** * @file Wrapper_nrlmsise00.h - * @brief Functions to wrap NRLMSISE-00 air density model in the ExternalLibrary + * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ #pragma once diff --git a/src/Library/optics/CMakeLists.txt b/src/library/optics/CMakeLists.txt similarity index 100% rename from src/Library/optics/CMakeLists.txt rename to src/library/optics/CMakeLists.txt diff --git a/src/Library/optics/GaussianBeamBase.cpp b/src/library/optics/GaussianBeamBase.cpp similarity index 98% rename from src/Library/optics/GaussianBeamBase.cpp rename to src/library/optics/GaussianBeamBase.cpp index 0dfa9d42b..3cfa2c5e9 100644 --- a/src/Library/optics/GaussianBeamBase.cpp +++ b/src/library/optics/GaussianBeamBase.cpp @@ -5,7 +5,7 @@ #include "GaussianBeamBase.h" -#include +#include #include GaussianBeamBase::GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt) diff --git a/src/Library/optics/GaussianBeamBase.h b/src/library/optics/GaussianBeamBase.h similarity index 100% rename from src/Library/optics/GaussianBeamBase.h rename to src/library/optics/GaussianBeamBase.h diff --git a/src/Library/sgp4/CMakeLists.txt b/src/library/sgp4/CMakeLists.txt similarity index 100% rename from src/Library/sgp4/CMakeLists.txt rename to src/library/sgp4/CMakeLists.txt diff --git a/src/Library/sgp4/sgp4ext.cpp b/src/library/sgp4/sgp4ext.cpp similarity index 100% rename from src/Library/sgp4/sgp4ext.cpp rename to src/library/sgp4/sgp4ext.cpp diff --git a/src/Library/sgp4/sgp4ext.h b/src/library/sgp4/sgp4ext.h similarity index 100% rename from src/Library/sgp4/sgp4ext.h rename to src/library/sgp4/sgp4ext.h diff --git a/src/Library/sgp4/sgp4io.cpp b/src/library/sgp4/sgp4io.cpp similarity index 100% rename from src/Library/sgp4/sgp4io.cpp rename to src/library/sgp4/sgp4io.cpp diff --git a/src/Library/sgp4/sgp4io.h b/src/library/sgp4/sgp4io.h similarity index 100% rename from src/Library/sgp4/sgp4io.h rename to src/library/sgp4/sgp4io.h diff --git a/src/Library/sgp4/sgp4unit.cpp b/src/library/sgp4/sgp4unit.cpp similarity index 99% rename from src/Library/sgp4/sgp4unit.cpp rename to src/library/sgp4/sgp4unit.cpp index 6e82c26f6..5a781ac51 100644 --- a/src/Library/sgp4/sgp4unit.cpp +++ b/src/library/sgp4/sgp4unit.cpp @@ -36,7 +36,7 @@ #include "sgp4unit.h" -#include +#include #include const char help = 'n'; diff --git a/src/Library/sgp4/sgp4unit.h b/src/library/sgp4/sgp4unit.h similarity index 100% rename from src/Library/sgp4/sgp4unit.h rename to src/library/sgp4/sgp4unit.h diff --git a/src/Library/utils/CMakeLists.txt b/src/library/utils/CMakeLists.txt similarity index 100% rename from src/Library/utils/CMakeLists.txt rename to src/library/utils/CMakeLists.txt diff --git a/src/Library/utils/ENDIAN_DEFINE.h b/src/library/utils/ENDIAN_DEFINE.h similarity index 100% rename from src/Library/utils/ENDIAN_DEFINE.h rename to src/library/utils/ENDIAN_DEFINE.h diff --git a/src/Library/utils/Macros.hpp b/src/library/utils/Macros.hpp similarity index 100% rename from src/Library/utils/Macros.hpp rename to src/library/utils/Macros.hpp diff --git a/src/Library/utils/endian.cpp b/src/library/utils/endian.cpp similarity index 100% rename from src/Library/utils/endian.cpp rename to src/library/utils/endian.cpp diff --git a/src/Library/utils/endian.h b/src/library/utils/endian.h similarity index 100% rename from src/Library/utils/endian.h rename to src/library/utils/endian.h diff --git a/src/Library/utils/slip.cpp b/src/library/utils/slip.cpp similarity index 100% rename from src/Library/utils/slip.cpp rename to src/library/utils/slip.cpp diff --git a/src/Library/utils/slip.h b/src/library/utils/slip.h similarity index 100% rename from src/Library/utils/slip.h rename to src/library/utils/slip.h diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index acf215a84..ad8a7c09c 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,8 +5,8 @@ #include "ground_station.hpp" -#include -#include +#include +#include #include #include #include diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 7fa8c3cf4..fb878c278 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include -#include +#include +#include #include #include diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp index ca2142f50..120868a8b 100644 --- a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp @@ -5,7 +5,7 @@ #include "inter_spacecraft_communication.hpp" -#include +#include InterSatComm::InterSatComm(const SimulationConfig* sim_config) { UNUSED(sim_config); } diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 1849cf560..4742a3039 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -5,7 +5,7 @@ #include "initialize_monte_carlo_parameters.hpp" -#include +#include using namespace std; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 8ad546f0c..d1b17b022 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index b737aeaeb..908034119 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ -#include +#include #include #include // #include "simulation_object.hpp" diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 13016b515..25bd6b1bf 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ -#include -#include +#include +#include #include #include #include diff --git a/src/simulation/spacecraft/installed_components.cpp b/src/simulation/spacecraft/installed_components.cpp index ce1118f1b..855727055 100644 --- a/src/simulation/spacecraft/installed_components.cpp +++ b/src/simulation/spacecraft/installed_components.cpp @@ -5,7 +5,7 @@ #include "installed_components.hpp" -#include +#include libra::Vector<3> InstalledComponents::GenerateForce_N_b() { libra::Vector<3> force_N_b_(0.0); diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index c0f04bf8a..d6aee2f0e 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include +#include #include /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index dc224361b..5ed01227b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include +#include #include #include #include diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index aba4fb30f..46d554db9 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,7 +5,7 @@ #include "sample_spacecraft.hpp" -#include +#include #include #include "sample_components.hpp" diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 174e62066..d767578a3 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include #define MIN_VAL 1e-6 diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 7a690df92..7f133e238 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ -#include -#include +#include +#include using libra::Matrix; using libra::Vector; diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 5094a9760..37ed4d09c 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ -#include +#include using libra::Vector; /** diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 8815d6eb8..ee4cd4735 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ -#include +#include using libra::Vector; /** From 9131a9e0ac22f7817300db24b6c2b6508ce9d3ae Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:20:49 +0100 Subject: [PATCH 0339/1086] Rename Geodesy directory --- CMakeLists.txt | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/library/{Geodesy => geodesy}/CMakeLists.txt | 0 src/library/{Geodesy => geodesy}/GeodeticPosition.cpp | 0 src/library/{Geodesy => geodesy}/GeodeticPosition.hpp | 0 src/simulation/ground_station/ground_station.hpp | 2 +- 6 files changed, 3 insertions(+), 3 deletions(-) rename src/library/{Geodesy => geodesy}/CMakeLists.txt (100%) rename src/library/{Geodesy => geodesy}/GeodeticPosition.cpp (100%) rename src/library/{Geodesy => geodesy}/GeodeticPosition.hpp (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 53c79ece4..16d98bb01 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -83,7 +83,7 @@ add_subdirectory(src/library/utils) add_subdirectory(src/library/optics) add_subdirectory(src/library/RelativeOrbit) add_subdirectory(src/library/Orbit) -add_subdirectory(src/library/Geodesy) +add_subdirectory(src/library/geodesy) set(SOURCE_FILES src/s2e.cpp diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index a04145fab..5813fb112 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,7 +16,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include #include diff --git a/src/library/Geodesy/CMakeLists.txt b/src/library/geodesy/CMakeLists.txt similarity index 100% rename from src/library/Geodesy/CMakeLists.txt rename to src/library/geodesy/CMakeLists.txt diff --git a/src/library/Geodesy/GeodeticPosition.cpp b/src/library/geodesy/GeodeticPosition.cpp similarity index 100% rename from src/library/Geodesy/GeodeticPosition.cpp rename to src/library/geodesy/GeodeticPosition.cpp diff --git a/src/library/Geodesy/GeodeticPosition.hpp b/src/library/geodesy/GeodeticPosition.hpp similarity index 100% rename from src/library/Geodesy/GeodeticPosition.hpp rename to src/library/geodesy/GeodeticPosition.hpp diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index fb878c278..9bd1b2a65 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include +#include #include #include #include From f9b54997029ee962da9a904f839ce81eb46209dd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:23:16 +0100 Subject: [PATCH 0340/1086] Rename GeodeticPosition --- src/dynamics/orbit/orbit.hpp | 2 +- src/library/geodesy/CMakeLists.txt | 2 +- .../{GeodeticPosition.cpp => geodetic_position.cpp} | 4 ++-- .../{GeodeticPosition.hpp => geodetic_position.hpp} | 8 ++++++-- src/simulation/ground_station/ground_station.hpp | 2 +- 5 files changed, 11 insertions(+), 7 deletions(-) rename src/library/geodesy/{GeodeticPosition.cpp => geodetic_position.cpp} (97%) rename src/library/geodesy/{GeodeticPosition.hpp => geodetic_position.hpp} (92%) diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 5813fb112..1d5446272 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -16,7 +16,7 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include +#include #include #include #include diff --git a/src/library/geodesy/CMakeLists.txt b/src/library/geodesy/CMakeLists.txt index 479ab6d63..61eb66efd 100644 --- a/src/library/geodesy/CMakeLists.txt +++ b/src/library/geodesy/CMakeLists.txt @@ -2,7 +2,7 @@ project(GEODESY) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - GeodeticPosition.cpp + geodetic_position.cpp ) include(../../../common.cmake) diff --git a/src/library/geodesy/GeodeticPosition.cpp b/src/library/geodesy/geodetic_position.cpp similarity index 97% rename from src/library/geodesy/GeodeticPosition.cpp rename to src/library/geodesy/geodetic_position.cpp index 1f29e2fbd..5dbf8f726 100644 --- a/src/library/geodesy/GeodeticPosition.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -1,8 +1,8 @@ /** - * @file GeodeticPosition.cpp + * @file geodetic_position.cpp * @brief Class to mange geodetic position expression */ -#include "GeodeticPosition.hpp" +#include "geodetic_position.hpp" #include // TODO: do not to use the functions in SGP4 library diff --git a/src/library/geodesy/GeodeticPosition.hpp b/src/library/geodesy/geodetic_position.hpp similarity index 92% rename from src/library/geodesy/GeodeticPosition.hpp rename to src/library/geodesy/geodetic_position.hpp index 3417247ca..e545431e5 100644 --- a/src/library/geodesy/GeodeticPosition.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -1,8 +1,10 @@ /** - * @file GeodeticPosition.hpp + * @file geodetic_position.hpp * @brief Class to mange geodetic position expression */ -#pragma once + +#ifndef S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ +#define S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ #include #include @@ -75,3 +77,5 @@ class GeodeticPosition { */ void CalcQuaternionXcxfToLtc(); }; + +#endif // S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ \ No newline at end of file diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 9bd1b2a65..60857302c 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#include +#include #include #include #include From a93d873e19fddae7c971506d286373d28de69b69 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:30:07 +0100 Subject: [PATCH 0341/1086] Rename utils directory --- CMakeLists.txt | 2 +- src/components/aocs/reaction_wheel_ode.cpp | 2 +- src/components/base_classes/component_base.hpp | 2 +- src/components/communication/antenna.cpp | 2 +- .../examples/example_serial_communication_for_hils.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.cpp | 2 +- src/dynamics/orbit/relative_orbit.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 2 +- src/dynamics/thermal/temperature.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/interface/hils/hils_port_manager.cpp | 2 +- src/interface/sils/ports/i2c_port.cpp | 2 +- src/library/math/RandomWalk_tfs.hpp | 2 +- src/library/sgp4/sgp4unit.cpp | 2 +- src/library/{utils => utilities}/CMakeLists.txt | 0 src/library/{utils => utilities}/ENDIAN_DEFINE.h | 0 src/library/{utils => utilities}/Macros.hpp | 0 src/library/{utils => utilities}/endian.cpp | 0 src/library/{utils => utilities}/endian.h | 0 src/library/{utils => utilities}/slip.cpp | 0 src/library/{utils => utilities}/slip.h | 0 src/simulation/ground_station/ground_station.cpp | 2 +- .../inter_spacecraft_communication.cpp | 2 +- src/simulation/spacecraft/installed_components.cpp | 2 +- 30 files changed, 23 insertions(+), 23 deletions(-) rename src/library/{utils => utilities}/CMakeLists.txt (100%) rename src/library/{utils => utilities}/ENDIAN_DEFINE.h (100%) rename src/library/{utils => utilities}/Macros.hpp (100%) rename src/library/{utils => utilities}/endian.cpp (100%) rename src/library/{utils => utilities}/endian.h (100%) rename src/library/{utils => utilities}/slip.cpp (100%) rename src/library/{utils => utilities}/slip.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 16d98bb01..c7b59d134 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -79,7 +79,7 @@ add_subdirectory(src/library/inih) add_subdirectory(src/library/math) add_subdirectory(src/library/nrlmsise00) add_subdirectory(src/library/sgp4) -add_subdirectory(src/library/utils) +add_subdirectory(src/library/utilities) add_subdirectory(src/library/optics) add_subdirectory(src/library/RelativeOrbit) add_subdirectory(src/library/Orbit) diff --git a/src/components/aocs/reaction_wheel_ode.cpp b/src/components/aocs/reaction_wheel_ode.cpp index 83f450c33..621053e5c 100644 --- a/src/components/aocs/reaction_wheel_ode.cpp +++ b/src/components/aocs/reaction_wheel_ode.cpp @@ -4,7 +4,7 @@ */ #include "reaction_wheel_ode.hpp" -#include +#include using namespace libra; diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index 19deb65f5..df6fdb93e 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ -#include +#include #include #include diff --git a/src/components/communication/antenna.cpp b/src/components/communication/antenna.cpp index cae68cadf..162360e2d 100644 --- a/src/components/communication/antenna.cpp +++ b/src/components/communication/antenna.cpp @@ -5,7 +5,7 @@ #include "antenna.hpp" -#include +#include #include Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index f3e47bee6..b686dbfbf 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -4,7 +4,7 @@ */ #include "example_serial_communication_for_hils.hpp" -#include +#include ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index d1a606a20..b036dc52c 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -7,7 +7,7 @@ #include "../library/math/NormalRand.hpp" using libra::NormalRand; -#include +#include #include "../library/math/GlobalRand.h" #include "../library/math/RandomWalk.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index bf9fb1e26..bcf10acf3 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ #define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ -#include +#include #include #include "../library/math/Vector.hpp" diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 8a7a660a4..7cf283502 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index e3e032741..fcd7b105f 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -5,7 +5,7 @@ #include "controlled_attitude.hpp" #include -#include +#include #include using namespace std; diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 1afb60aff..50f094175 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -5,7 +5,7 @@ #include "encke_orbit_propagation.hpp" -#include +#include #include "../../library/Orbit/OrbitalElements.h" diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 230d4d75a..0954f1087 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -4,7 +4,7 @@ */ #include "kepler_orbit_propagation.hpp" -#include +#include #include "../../library/math/s2e_math.hpp" diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 6b3448d09..1f4462841 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -4,7 +4,7 @@ */ #include "relative_orbit.hpp" -#include +#include #include "rk4_orbit_propagation.hpp" diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 455bcbf5b..7fcd44972 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -4,7 +4,7 @@ */ #include "rk4_orbit_propagation.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index be4ae5246..2a6c17622 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -5,7 +5,7 @@ #include "sgp4_orbit_propagation.hpp" -#include +#include #include #include using namespace std; diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index c241c193e..4941e9999 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -5,7 +5,7 @@ #include "temperature.hpp" -#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 447e51dd5..942acc8bb 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -9,7 +9,7 @@ #include //for gstime() #include -#include +#include #include #include #include diff --git a/src/interface/hils/hils_port_manager.cpp b/src/interface/hils/hils_port_manager.cpp index 210235bfa..19572ecaf 100644 --- a/src/interface/hils/hils_port_manager.cpp +++ b/src/interface/hils/hils_port_manager.cpp @@ -5,7 +5,7 @@ #include "hils_port_manager.hpp" -#include +#include // #define HILS_PORT_MANAGER_SHOW_DEBUG_DATA diff --git a/src/interface/sils/ports/i2c_port.cpp b/src/interface/sils/ports/i2c_port.cpp index acb532ae9..5525d2f4e 100644 --- a/src/interface/sils/ports/i2c_port.cpp +++ b/src/interface/sils/ports/i2c_port.cpp @@ -5,7 +5,7 @@ #include "i2c_port.hpp" -#include +#include I2CPort::I2CPort(void) {} diff --git a/src/library/math/RandomWalk_tfs.hpp b/src/library/math/RandomWalk_tfs.hpp index 9a726809b..e35cb5860 100644 --- a/src/library/math/RandomWalk_tfs.hpp +++ b/src/library/math/RandomWalk_tfs.hpp @@ -7,7 +7,7 @@ #include -#include +#include template RandomWalk::RandomWalk(double step_width, const libra::Vector& stddev, const libra::Vector& limit) diff --git a/src/library/sgp4/sgp4unit.cpp b/src/library/sgp4/sgp4unit.cpp index 5a781ac51..9e9836112 100644 --- a/src/library/sgp4/sgp4unit.cpp +++ b/src/library/sgp4/sgp4unit.cpp @@ -36,7 +36,7 @@ #include "sgp4unit.h" -#include +#include #include const char help = 'n'; diff --git a/src/library/utils/CMakeLists.txt b/src/library/utilities/CMakeLists.txt similarity index 100% rename from src/library/utils/CMakeLists.txt rename to src/library/utilities/CMakeLists.txt diff --git a/src/library/utils/ENDIAN_DEFINE.h b/src/library/utilities/ENDIAN_DEFINE.h similarity index 100% rename from src/library/utils/ENDIAN_DEFINE.h rename to src/library/utilities/ENDIAN_DEFINE.h diff --git a/src/library/utils/Macros.hpp b/src/library/utilities/Macros.hpp similarity index 100% rename from src/library/utils/Macros.hpp rename to src/library/utilities/Macros.hpp diff --git a/src/library/utils/endian.cpp b/src/library/utilities/endian.cpp similarity index 100% rename from src/library/utils/endian.cpp rename to src/library/utilities/endian.cpp diff --git a/src/library/utils/endian.h b/src/library/utilities/endian.h similarity index 100% rename from src/library/utils/endian.h rename to src/library/utilities/endian.h diff --git a/src/library/utils/slip.cpp b/src/library/utilities/slip.cpp similarity index 100% rename from src/library/utils/slip.cpp rename to src/library/utilities/slip.cpp diff --git a/src/library/utils/slip.h b/src/library/utilities/slip.h similarity index 100% rename from src/library/utils/slip.h rename to src/library/utilities/slip.h diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index ad8a7c09c..0c02561b0 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,7 +6,7 @@ #include "ground_station.hpp" #include -#include +#include #include #include #include diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp index 120868a8b..951e559b2 100644 --- a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp @@ -5,7 +5,7 @@ #include "inter_spacecraft_communication.hpp" -#include +#include InterSatComm::InterSatComm(const SimulationConfig* sim_config) { UNUSED(sim_config); } diff --git a/src/simulation/spacecraft/installed_components.cpp b/src/simulation/spacecraft/installed_components.cpp index 855727055..2879bc41e 100644 --- a/src/simulation/spacecraft/installed_components.cpp +++ b/src/simulation/spacecraft/installed_components.cpp @@ -5,7 +5,7 @@ #include "installed_components.hpp" -#include +#include libra::Vector<3> InstalledComponents::GenerateForce_N_b() { libra::Vector<3> force_N_b_(0.0); From 3204c8353a2cc7340a1d915cc878b635052428dc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:31:57 +0100 Subject: [PATCH 0342/1086] Rename ENDIAN_DEFINE --- src/library/utilities/endian.h | 2 +- .../utilities/{ENDIAN_DEFINE.h => endian_define.hpp} | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) rename src/library/utilities/{ENDIAN_DEFINE.h => endian_define.hpp} (53%) diff --git a/src/library/utilities/endian.h b/src/library/utilities/endian.h index de734c3b8..2e4f140a2 100644 --- a/src/library/utilities/endian.h +++ b/src/library/utilities/endian.h @@ -8,7 +8,7 @@ #include #include -#include "ENDIAN_DEFINE.h" // for IS_LITTLE_ENDIAN +#include "endian_define.hpp" // for IS_LITTLE_ENDIAN /** * @fn endian_memcpy diff --git a/src/library/utilities/ENDIAN_DEFINE.h b/src/library/utilities/endian_define.hpp similarity index 53% rename from src/library/utilities/ENDIAN_DEFINE.h rename to src/library/utilities/endian_define.hpp index 8f6de1adc..2fd25eb21 100644 --- a/src/library/utilities/ENDIAN_DEFINE.h +++ b/src/library/utilities/endian_define.hpp @@ -1,10 +1,10 @@ /** - * @file ENDIAN_DEFINE.h + * @file endian_define.hpp * @brief Define macro to change the endian definition */ -#ifndef ENDIAN_DEFINE_H_ -#define ENDIAN_DEFINE_H_ +#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ +#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ #ifndef IS_LITTLE_ENDIAN @@ -12,4 +12,4 @@ #endif // IS_LITTLE_ENDIAN -#endif // ENDIAN_DEFINE_H_ +#endif // #ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ From 53511e81487c8d5053950d43df145b28e70b9ac9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:33:30 +0100 Subject: [PATCH 0343/1086] Fix #define guard --- src/library/utilities/endian.h | 7 +++++-- src/library/utilities/endian_define.hpp | 2 +- src/library/utilities/slip.h | 5 ++++- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/library/utilities/endian.h b/src/library/utilities/endian.h index 2e4f140a2..a593e045c 100644 --- a/src/library/utilities/endian.h +++ b/src/library/utilities/endian.h @@ -3,7 +3,8 @@ * @brief Function to consider the endian */ -#pragma once +#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_H_ +#define S2E_LIBRARY_UTILITIES_ENDIAN_H_ #include #include @@ -17,4 +18,6 @@ * @param [in] src: Copy source * @param [in] count: Copy data size */ -void *endian_memcpy(void *dst, const void *src, size_t count); \ No newline at end of file +void *endian_memcpy(void *dst, const void *src, size_t count); + +#endif // S2E_LIBRARY_UTILITIES_ENDIAN_H_ \ No newline at end of file diff --git a/src/library/utilities/endian_define.hpp b/src/library/utilities/endian_define.hpp index 2fd25eb21..bd2e5195b 100644 --- a/src/library/utilities/endian_define.hpp +++ b/src/library/utilities/endian_define.hpp @@ -4,7 +4,7 @@ */ #ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ -#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ +#define S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ #ifndef IS_LITTLE_ENDIAN diff --git a/src/library/utilities/slip.h b/src/library/utilities/slip.h index cde0a26f2..070ab6d9e 100644 --- a/src/library/utilities/slip.h +++ b/src/library/utilities/slip.h @@ -3,7 +3,8 @@ * @brief Functions for SLIP(Serial Line Internet Protocol) encoding */ -#pragma once +#ifndef S2E_LIBRARY_UTILITIES_SLIP_H_ +#define S2E_LIBRARY_UTILITIES_SLIP_H_ #include @@ -38,3 +39,5 @@ std::vector encode_slip(std::vector in); * @return Encoded data */ std::vector encode_slip_with_header(std::vector in); + +#endif // S2E_LIBRARY_UTILITIES_SLIP_H_ \ No newline at end of file From 2338c73308b379244430e0155611887cc9a964e1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:35:38 +0100 Subject: [PATCH 0344/1086] Rename Macros --- src/components/aocs/reaction_wheel_ode.cpp | 2 +- src/components/base_classes/component_base.hpp | 2 +- src/components/communication/antenna.cpp | 2 +- .../example_serial_communication_for_hils.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.cpp | 2 +- src/dynamics/orbit/relative_orbit.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 2 +- src/dynamics/thermal/temperature.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/interface/hils/hils_port_manager.cpp | 2 +- src/interface/sils/ports/i2c_port.cpp | 2 +- src/library/math/RandomWalk_tfs.hpp | 2 +- src/library/sgp4/sgp4unit.cpp | 2 +- src/library/utilities/Macros.hpp | 8 -------- src/library/utilities/macros.hpp | 11 +++++++++++ src/library/utilities/slip.h | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- .../inter_spacecraft_communication.cpp | 2 +- src/simulation/spacecraft/installed_components.cpp | 2 +- 25 files changed, 34 insertions(+), 31 deletions(-) delete mode 100644 src/library/utilities/Macros.hpp create mode 100644 src/library/utilities/macros.hpp diff --git a/src/components/aocs/reaction_wheel_ode.cpp b/src/components/aocs/reaction_wheel_ode.cpp index 621053e5c..19efb3642 100644 --- a/src/components/aocs/reaction_wheel_ode.cpp +++ b/src/components/aocs/reaction_wheel_ode.cpp @@ -4,7 +4,7 @@ */ #include "reaction_wheel_ode.hpp" -#include +#include using namespace libra; diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index df6fdb93e..26ed8571d 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ -#include +#include #include #include diff --git a/src/components/communication/antenna.cpp b/src/components/communication/antenna.cpp index 162360e2d..ab2f4ab86 100644 --- a/src/components/communication/antenna.cpp +++ b/src/components/communication/antenna.cpp @@ -5,7 +5,7 @@ #include "antenna.hpp" -#include +#include #include Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index b686dbfbf..77e8584f5 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -4,7 +4,7 @@ */ #include "example_serial_communication_for_hils.hpp" -#include +#include ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index b036dc52c..92cc68171 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -7,7 +7,7 @@ #include "../library/math/NormalRand.hpp" using libra::NormalRand; -#include +#include #include "../library/math/GlobalRand.h" #include "../library/math/RandomWalk.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index bcf10acf3..bb13ca1d6 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ #define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ -#include +#include #include #include "../library/math/Vector.hpp" diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 7cf283502..5dfa6da43 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index fcd7b105f..9f3e3b136 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -5,7 +5,7 @@ #include "controlled_attitude.hpp" #include -#include +#include #include using namespace std; diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 50f094175..8abe14b25 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -5,7 +5,7 @@ #include "encke_orbit_propagation.hpp" -#include +#include #include "../../library/Orbit/OrbitalElements.h" diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 0954f1087..5d37926a3 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -4,7 +4,7 @@ */ #include "kepler_orbit_propagation.hpp" -#include +#include #include "../../library/math/s2e_math.hpp" diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 1f4462841..ebd84b487 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -4,7 +4,7 @@ */ #include "relative_orbit.hpp" -#include +#include #include "rk4_orbit_propagation.hpp" diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 7fcd44972..106402df9 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -4,7 +4,7 @@ */ #include "rk4_orbit_propagation.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 2a6c17622..a4ff1bba4 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -5,7 +5,7 @@ #include "sgp4_orbit_propagation.hpp" -#include +#include #include #include using namespace std; diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index 4941e9999..6370cae82 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -5,7 +5,7 @@ #include "temperature.hpp" -#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 942acc8bb..305685cef 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -9,7 +9,7 @@ #include //for gstime() #include -#include +#include #include #include #include diff --git a/src/interface/hils/hils_port_manager.cpp b/src/interface/hils/hils_port_manager.cpp index 19572ecaf..65ce0f9ca 100644 --- a/src/interface/hils/hils_port_manager.cpp +++ b/src/interface/hils/hils_port_manager.cpp @@ -5,7 +5,7 @@ #include "hils_port_manager.hpp" -#include +#include // #define HILS_PORT_MANAGER_SHOW_DEBUG_DATA diff --git a/src/interface/sils/ports/i2c_port.cpp b/src/interface/sils/ports/i2c_port.cpp index 5525d2f4e..7a753e7ad 100644 --- a/src/interface/sils/ports/i2c_port.cpp +++ b/src/interface/sils/ports/i2c_port.cpp @@ -5,7 +5,7 @@ #include "i2c_port.hpp" -#include +#include I2CPort::I2CPort(void) {} diff --git a/src/library/math/RandomWalk_tfs.hpp b/src/library/math/RandomWalk_tfs.hpp index e35cb5860..8e1266c4d 100644 --- a/src/library/math/RandomWalk_tfs.hpp +++ b/src/library/math/RandomWalk_tfs.hpp @@ -7,7 +7,7 @@ #include -#include +#include template RandomWalk::RandomWalk(double step_width, const libra::Vector& stddev, const libra::Vector& limit) diff --git a/src/library/sgp4/sgp4unit.cpp b/src/library/sgp4/sgp4unit.cpp index 9e9836112..a9c7818cc 100644 --- a/src/library/sgp4/sgp4unit.cpp +++ b/src/library/sgp4/sgp4unit.cpp @@ -36,7 +36,7 @@ #include "sgp4unit.h" -#include +#include #include const char help = 'n'; diff --git a/src/library/utilities/Macros.hpp b/src/library/utilities/Macros.hpp deleted file mode 100644 index 23e95a3cb..000000000 --- a/src/library/utilities/Macros.hpp +++ /dev/null @@ -1,8 +0,0 @@ -/** - * @file Macros.h - * @brief Definition of commonly used macros - */ - -#pragma once - -#define UNUSED(x) (void)(x) //!< Macro to avoid unused warnings diff --git a/src/library/utilities/macros.hpp b/src/library/utilities/macros.hpp new file mode 100644 index 000000000..a17c07572 --- /dev/null +++ b/src/library/utilities/macros.hpp @@ -0,0 +1,11 @@ +/** + * @file macros.hpp + * @brief Definition of commonly used macros + */ + +#ifndef S2E_LIBRARY_UTILITIES_MACROS_H_ +#define S2E_LIBRARY_UTILITIES_MACROS_H_ + +#define UNUSED(x) (void)(x) //!< Macro to avoid unused warnings + +#endif // S2E_LIBRARY_UTILITIES_MACROS_H_ diff --git a/src/library/utilities/slip.h b/src/library/utilities/slip.h index 070ab6d9e..602752b15 100644 --- a/src/library/utilities/slip.h +++ b/src/library/utilities/slip.h @@ -40,4 +40,4 @@ std::vector encode_slip(std::vector in); */ std::vector encode_slip_with_header(std::vector in); -#endif // S2E_LIBRARY_UTILITIES_SLIP_H_ \ No newline at end of file +#endif // S2E_LIBRARY_UTILITIES_SLIP_H_ diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 0c02561b0..414b03a94 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,7 +6,7 @@ #include "ground_station.hpp" #include -#include +#include #include #include #include diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp index 951e559b2..91e9ed044 100644 --- a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp @@ -5,7 +5,7 @@ #include "inter_spacecraft_communication.hpp" -#include +#include InterSatComm::InterSatComm(const SimulationConfig* sim_config) { UNUSED(sim_config); } diff --git a/src/simulation/spacecraft/installed_components.cpp b/src/simulation/spacecraft/installed_components.cpp index 2879bc41e..6f5aa13c9 100644 --- a/src/simulation/spacecraft/installed_components.cpp +++ b/src/simulation/spacecraft/installed_components.cpp @@ -5,7 +5,7 @@ #include "installed_components.hpp" -#include +#include libra::Vector<3> InstalledComponents::GenerateForce_N_b() { libra::Vector<3> force_N_b_(0.0); From 72cc7d4c4020b17c37ecd4e85541546348afdf63 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:39:22 +0100 Subject: [PATCH 0345/1086] Fix #define guard --- src/components/examples/example_change_structure.hpp | 5 ++++- .../examples/example_i2c_controller_for_hils.hpp | 7 ++++++- src/components/examples/example_i2c_target_for_hils.hpp | 6 +++++- .../examples/example_serial_communication_for_hils.hpp | 7 ++++++- .../examples/example_serial_communication_with_obc.hpp | 6 +++++- 5 files changed, 26 insertions(+), 5 deletions(-) diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 148f30604..1187683a5 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -3,7 +3,8 @@ * @brief Class to show an example to change satellite structure information */ -#pragma once +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ #include #include @@ -51,3 +52,5 @@ class ExampleChangeStructure : public ComponentBase, public ILoggable { protected: Structure* structure_; //!< Structure information }; + +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index e75fbbcb0..b8d92f66a 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -2,7 +2,10 @@ * @file example_i2c_controller_for_hils.hpp * @brief Example of component emulation for I2C controller side communication in HILS environment */ -#pragma once + +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ + #include #include "../base_classes/component_base.hpp" @@ -61,3 +64,5 @@ class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCo static const uint8_t kWriteCmd_ = 0x44; //!< Write command for SC18IM700 static const uint8_t kCmdFooter_ = 0x50; //!< 'P' Footer for SC18IM700 }; + +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index da2e8a870..8f72b0077 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -3,7 +3,9 @@ * @brief Example of component emulation for I2C target side communication in HILS environment */ -#pragma once +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ + #include #include "../base_classes/component_base.hpp" @@ -51,3 +53,5 @@ class ExampleI2cTargetForHils : public ComponentBase, public ObcI2cTargetCommuni const unsigned int kStoredFrameSize = 3; //!< Frame size const unsigned char kNumAlphabet = 26; //!< Number of alphabet }; + +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 1a696aa57..29b6c16d3 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -2,7 +2,10 @@ * @file example_serial_communication_for_hils.hpp * @brief Example of component emulation for UART communication in HILS environment */ -#pragma once + +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ + #include #include "../base_classes/component_base.hpp" @@ -67,3 +70,5 @@ class ExampleSerialCommunicationForHils : public ComponentBase, public ObcCommun */ int GenerateTelemetry() override; }; + +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 5a6627d31..9102426e0 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -3,7 +3,9 @@ * @brief Example of component emulation with communication between OBC Flight software */ -#pragma once +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ + #include #include "../base_classes/component_base.hpp" @@ -89,3 +91,5 @@ class ExampleSerialCommunicationWithObc : public ComponentBase, public ObcCommun */ int Initialize(); }; + +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ From 2a1b6343ec534f66f80ba150b847d4b6c790b5a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:42:02 +0100 Subject: [PATCH 0346/1086] Rename GaussianBeam --- src/library/optics/CMakeLists.txt | 2 +- .../{GaussianBeamBase.cpp => gaussian_beam_base.cpp} | 4 ++-- .../optics/{GaussianBeamBase.h => gaussian_beam_base.hpp} | 8 ++++++-- 3 files changed, 9 insertions(+), 5 deletions(-) rename src/library/optics/{GaussianBeamBase.cpp => gaussian_beam_base.cpp} (96%) rename src/library/optics/{GaussianBeamBase.h => gaussian_beam_base.hpp} (94%) diff --git a/src/library/optics/CMakeLists.txt b/src/library/optics/CMakeLists.txt index 8bed0dd67..165dbed4c 100644 --- a/src/library/optics/CMakeLists.txt +++ b/src/library/optics/CMakeLists.txt @@ -2,7 +2,7 @@ project(OPTICS) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - GaussianBeamBase.cpp + gaussian_beam_base.cpp ) include(../../../common.cmake) diff --git a/src/library/optics/GaussianBeamBase.cpp b/src/library/optics/gaussian_beam_base.cpp similarity index 96% rename from src/library/optics/GaussianBeamBase.cpp rename to src/library/optics/gaussian_beam_base.cpp index 3cfa2c5e9..b70b64d2e 100644 --- a/src/library/optics/GaussianBeamBase.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -1,9 +1,9 @@ /** - * @file GaussianBeamBase.cpp + * @file gaussian_beam_base.cpp * @brief Class to express gaussian beam laser */ -#include "GaussianBeamBase.h" +#include "gaussian_beam_base.hpp" #include #include diff --git a/src/library/optics/GaussianBeamBase.h b/src/library/optics/gaussian_beam_base.hpp similarity index 94% rename from src/library/optics/GaussianBeamBase.h rename to src/library/optics/gaussian_beam_base.hpp index 1a88dec74..940fb1caf 100644 --- a/src/library/optics/GaussianBeamBase.h +++ b/src/library/optics/gaussian_beam_base.hpp @@ -1,9 +1,11 @@ /** - * @file GaussianBeamBase.h + * @file gaussian_beam_base.hpp * @brief Class to express gaussian beam laser */ -#pragma once +#ifndef S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ +#define S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ + #include "../math/Vector.hpp" /** @@ -104,3 +106,5 @@ class GaussianBeamBase { libra::Vector<3> pointing_vector_i_{0.0}; //!< Pointing direction vector in the inertial frame libra::Vector<3> pos_beamwaist_i_{0.0}; //!< Position of beam waist in the inertial frame [m] (Not used?) }; + +#endif // S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ From fe451340ff2953a7edc534f1ba6284b89fd53d66 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:45:31 +0100 Subject: [PATCH 0347/1086] Rename NRLMSISE --- src/environment/local/atmosphere.hpp | 2 +- src/library/nrlmsise00/CMakeLists.txt | 4 ++-- .../{Wrapper_nrlmsise00.cpp => wrapper_nrlmsise00.cpp} | 4 ++-- .../{Wrapper_nrlmsise00.h => wrapper_nrlmsise00.hpp} | 9 ++++----- 4 files changed, 9 insertions(+), 10 deletions(-) rename src/library/nrlmsise00/{Wrapper_nrlmsise00.cpp => wrapper_nrlmsise00.cpp} (99%) rename src/library/nrlmsise00/{Wrapper_nrlmsise00.h => wrapper_nrlmsise00.hpp} (93%) diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 7c3a44fc8..6cdaddf12 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,7 +7,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#include +#include #include #include diff --git a/src/library/nrlmsise00/CMakeLists.txt b/src/library/nrlmsise00/CMakeLists.txt index 284066bd4..f3156ecb2 100644 --- a/src/library/nrlmsise00/CMakeLists.txt +++ b/src/library/nrlmsise00/CMakeLists.txt @@ -2,8 +2,8 @@ project(WRAPPER_NRLMSISE00) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - Wrapper_nrlmsise00.cpp - Wrapper_nrlmsise00.h + wrapper_nrlmsise00.cpp + wrapper_nrlmsise00.hpp ) include(../../../common.cmake) diff --git a/src/library/nrlmsise00/Wrapper_nrlmsise00.cpp b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp similarity index 99% rename from src/library/nrlmsise00/Wrapper_nrlmsise00.cpp rename to src/library/nrlmsise00/wrapper_nrlmsise00.cpp index f95ad59b7..9cf813a6b 100644 --- a/src/library/nrlmsise00/Wrapper_nrlmsise00.cpp +++ b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp @@ -1,5 +1,5 @@ /** - * @file Wrapper_nrlmsise00.cpp + * @file wrapper_nrlmsise00.cpp * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ @@ -19,7 +19,7 @@ extern "C" { #include #include -#include "Wrapper_nrlmsise00.h" /* header for nrlmsise-00.h */ +#include "wrapper_nrlmsise00.hpp" /* header for nrlmsise-00.h */ using namespace std; diff --git a/src/library/nrlmsise00/Wrapper_nrlmsise00.h b/src/library/nrlmsise00/wrapper_nrlmsise00.hpp similarity index 93% rename from src/library/nrlmsise00/Wrapper_nrlmsise00.h rename to src/library/nrlmsise00/wrapper_nrlmsise00.hpp index c66bfb559..44af765cf 100644 --- a/src/library/nrlmsise00/Wrapper_nrlmsise00.h +++ b/src/library/nrlmsise00/wrapper_nrlmsise00.hpp @@ -1,11 +1,10 @@ /** - * @file Wrapper_nrlmsise00.h + * @file wrapper_nrlmsise00.hpp * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ -#pragma once -#ifndef __wrapper_nrlmsise00_H__ -#define __wrapper_nrlmsise00_H__ +#ifndef S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ +#define S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ #include #include @@ -75,4 +74,4 @@ int GetSpaceWeatherTable_(double decyear, double endsec, const std::string& file #define __inline_double double #endif -#endif //__wrapper_nrlmsise00_H__ +#endif // S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ From ef6baf5ce00eb03639a1063b285831eb2400f99d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:49:09 +0100 Subject: [PATCH 0348/1086] Rename Orbit directoryu --- CMakeLists.txt | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.hpp | 2 +- src/dynamics/orbit/initialize_orbit.hpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.hpp | 2 +- src/library/{Orbit => orbit}/CMakeLists.txt | 0 src/library/{Orbit => orbit}/KeplerOrbit.cpp | 0 src/library/{Orbit => orbit}/KeplerOrbit.h | 0 src/library/{Orbit => orbit}/OrbitalElements.cpp | 0 src/library/{Orbit => orbit}/OrbitalElements.h | 0 10 files changed, 5 insertions(+), 5 deletions(-) rename src/library/{Orbit => orbit}/CMakeLists.txt (100%) rename src/library/{Orbit => orbit}/KeplerOrbit.cpp (100%) rename src/library/{Orbit => orbit}/KeplerOrbit.h (100%) rename src/library/{Orbit => orbit}/OrbitalElements.cpp (100%) rename src/library/{Orbit => orbit}/OrbitalElements.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index c7b59d134..8b857359f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -82,7 +82,7 @@ add_subdirectory(src/library/sgp4) add_subdirectory(src/library/utilities) add_subdirectory(src/library/optics) add_subdirectory(src/library/RelativeOrbit) -add_subdirectory(src/library/Orbit) +add_subdirectory(src/library/orbit) add_subdirectory(src/library/geodesy) set(SOURCE_FILES diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 8abe14b25..0efd1051e 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -7,7 +7,7 @@ #include -#include "../../library/Orbit/OrbitalElements.h" +#include "../../library/orbit/OrbitalElements.h" EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celes_info, const double mu_m3_s2, const double prop_step_s, const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index d857026f7..9f7883f54 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ -#include "../../library/Orbit/KeplerOrbit.h" +#include "../../library/orbit/KeplerOrbit.h" #include "../../library/math/ODE.hpp" #include "orbit.hpp" diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index ce9800346..4e111ae8b 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ -#include +#include #include "orbit.hpp" diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index c923b1a3b..c42f9df7a 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ -#include "../../library/Orbit/KeplerOrbit.h" +#include "../../library/orbit/KeplerOrbit.h" #include "orbit.hpp" /** diff --git a/src/library/Orbit/CMakeLists.txt b/src/library/orbit/CMakeLists.txt similarity index 100% rename from src/library/Orbit/CMakeLists.txt rename to src/library/orbit/CMakeLists.txt diff --git a/src/library/Orbit/KeplerOrbit.cpp b/src/library/orbit/KeplerOrbit.cpp similarity index 100% rename from src/library/Orbit/KeplerOrbit.cpp rename to src/library/orbit/KeplerOrbit.cpp diff --git a/src/library/Orbit/KeplerOrbit.h b/src/library/orbit/KeplerOrbit.h similarity index 100% rename from src/library/Orbit/KeplerOrbit.h rename to src/library/orbit/KeplerOrbit.h diff --git a/src/library/Orbit/OrbitalElements.cpp b/src/library/orbit/OrbitalElements.cpp similarity index 100% rename from src/library/Orbit/OrbitalElements.cpp rename to src/library/orbit/OrbitalElements.cpp diff --git a/src/library/Orbit/OrbitalElements.h b/src/library/orbit/OrbitalElements.h similarity index 100% rename from src/library/Orbit/OrbitalElements.h rename to src/library/orbit/OrbitalElements.h From 60287e8be4d201818e798849afb5ffbe85589e3c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:50:56 +0100 Subject: [PATCH 0349/1086] Rename KeplerOrbit --- src/dynamics/orbit/encke_orbit_propagation.hpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.hpp | 2 +- src/library/orbit/CMakeLists.txt | 2 +- src/library/orbit/{KeplerOrbit.cpp => kepler_orbit.cpp} | 4 ++-- src/library/orbit/{KeplerOrbit.h => kepler_orbit.hpp} | 9 +++++++-- 5 files changed, 12 insertions(+), 7 deletions(-) rename src/library/orbit/{KeplerOrbit.cpp => kepler_orbit.cpp} (98%) rename src/library/orbit/{KeplerOrbit.h => kepler_orbit.hpp} (93%) diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 9f7883f54..86217d3e8 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ -#include "../../library/orbit/KeplerOrbit.h" +#include "../../library/orbit/kepler_orbit.hpp" #include "../../library/math/ODE.hpp" #include "orbit.hpp" diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index c42f9df7a..ef3895928 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ -#include "../../library/orbit/KeplerOrbit.h" +#include "../../library/orbit/kepler_orbit.hpp" #include "orbit.hpp" /** diff --git a/src/library/orbit/CMakeLists.txt b/src/library/orbit/CMakeLists.txt index 9d94006ba..93ce34b28 100644 --- a/src/library/orbit/CMakeLists.txt +++ b/src/library/orbit/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10) add_library(${PROJECT_NAME} STATIC OrbitalElements.cpp - KeplerOrbit.cpp + kepler_orbit.cpp ) include(../../../common.cmake) diff --git a/src/library/orbit/KeplerOrbit.cpp b/src/library/orbit/kepler_orbit.cpp similarity index 98% rename from src/library/orbit/KeplerOrbit.cpp rename to src/library/orbit/kepler_orbit.cpp index 7aee99c95..f9e33d34f 100644 --- a/src/library/orbit/KeplerOrbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -1,8 +1,8 @@ /** - * @file KeplerOrbit.cpp + * @file kepler_orbit.cpp * @brief Class to calculate Kepler orbit calculation */ -#include "KeplerOrbit.h" +#include "kepler_orbit.hpp" #include "../math/MatVec.hpp" #include "../math/s2e_math.hpp" diff --git a/src/library/orbit/KeplerOrbit.h b/src/library/orbit/kepler_orbit.hpp similarity index 93% rename from src/library/orbit/KeplerOrbit.h rename to src/library/orbit/kepler_orbit.hpp index 02b41df6e..1eef688b9 100644 --- a/src/library/orbit/KeplerOrbit.h +++ b/src/library/orbit/kepler_orbit.hpp @@ -1,8 +1,11 @@ /** - * @file KeplerOrbit.h + * @file kepler_orbit.hpp * @brief Class to calculate Kepler orbit calculation */ -#pragma once + +#ifndef S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ +#define S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ + #include "../math/Matrix.hpp" #include "../math/Vector.hpp" #include "./OrbitalElements.h" @@ -74,3 +77,5 @@ class KeplerOrbit { */ double SolveKeplerFirstOrder(const double eccentricity, const double mean_anomaly_rad, const double angle_limit_rad, const int iteration_limit); }; + +#endif // S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ From b423790e8405891bf016ff1cfae9d15084fd48c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:52:47 +0100 Subject: [PATCH 0350/1086] Rename OrbitalElements --- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/initialize_orbit.hpp | 2 +- src/library/orbit/CMakeLists.txt | 2 +- src/library/orbit/kepler_orbit.hpp | 2 +- .../orbit/{OrbitalElements.cpp => orbital_elements.cpp} | 4 ++-- .../orbit/{OrbitalElements.h => orbital_elements.hpp} | 8 ++++++-- 6 files changed, 12 insertions(+), 8 deletions(-) rename src/library/orbit/{OrbitalElements.cpp => orbital_elements.cpp} (98%) rename src/library/orbit/{OrbitalElements.h => orbital_elements.hpp} (94%) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 0efd1051e..b1e8c6758 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -7,7 +7,7 @@ #include -#include "../../library/orbit/OrbitalElements.h" +#include "../../library/orbit/orbital_elements.hpp" EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celes_info, const double mu_m3_s2, const double prop_step_s, const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index 4e111ae8b..515235859 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ -#include +#include #include "orbit.hpp" diff --git a/src/library/orbit/CMakeLists.txt b/src/library/orbit/CMakeLists.txt index 93ce34b28..57db48492 100644 --- a/src/library/orbit/CMakeLists.txt +++ b/src/library/orbit/CMakeLists.txt @@ -2,7 +2,7 @@ project(ORBIT_MODELS) cmake_minimum_required(VERSION 3.10) add_library(${PROJECT_NAME} STATIC - OrbitalElements.cpp + orbital_elements.cpp kepler_orbit.cpp ) diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 1eef688b9..4bffa5647 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -8,7 +8,7 @@ #include "../math/Matrix.hpp" #include "../math/Vector.hpp" -#include "./OrbitalElements.h" +#include "./orbital_elements.hpp" /** * @class KeplerOrbit diff --git a/src/library/orbit/OrbitalElements.cpp b/src/library/orbit/orbital_elements.cpp similarity index 98% rename from src/library/orbit/OrbitalElements.cpp rename to src/library/orbit/orbital_elements.cpp index c2e14eeeb..7ae918e52 100644 --- a/src/library/orbit/OrbitalElements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -1,9 +1,9 @@ /** - * @file OrbitalElements.cpp + * @file orbital_elements.cpp * @brief Class for classical orbital elements */ -#include "OrbitalElements.h" +#include "orbital_elements.hpp" #include diff --git a/src/library/orbit/OrbitalElements.h b/src/library/orbit/orbital_elements.hpp similarity index 94% rename from src/library/orbit/OrbitalElements.h rename to src/library/orbit/orbital_elements.hpp index af4604d5d..0f19fc657 100644 --- a/src/library/orbit/OrbitalElements.h +++ b/src/library/orbit/orbital_elements.hpp @@ -1,9 +1,11 @@ /** - * @file OrbitalElements.h + * @file orbital_elements.hpp * @brief Class for classical orbital elements */ -#pragma once +#ifndef S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ +#define S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ + #include "../math/Vector.hpp" /** @@ -92,3 +94,5 @@ class OrbitalElements { // Calculation of Orbital Elements from Position and Velocity void CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> r_i_m, const libra::Vector<3> v_i_m_s); }; + +#endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ From 0ee9f5acc0b551bc0da75cd8070eff7c22fe5d43 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 15:59:13 +0100 Subject: [PATCH 0351/1086] Rename ReletiveOrbitModels --- CMakeLists.txt | 3 +-- src/dynamics/orbit/relative_orbit.hpp | 3 +-- src/library/RelativeOrbit/CMakeLists.txt | 8 -------- src/library/orbit/CMakeLists.txt | 1 + .../relative_orbit_models.cpp} | 4 ++-- .../relative_orbit_models.hpp} | 10 +++++++--- 6 files changed, 12 insertions(+), 17 deletions(-) delete mode 100644 src/library/RelativeOrbit/CMakeLists.txt rename src/library/{RelativeOrbit/RelativeOrbitModels.cpp => orbit/relative_orbit_models.cpp} (97%) rename src/library/{RelativeOrbit/RelativeOrbitModels.h => orbit/relative_orbit_models.hpp} (82%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8b857359f..2a35cbf0a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -81,7 +81,6 @@ add_subdirectory(src/library/nrlmsise00) add_subdirectory(src/library/sgp4) add_subdirectory(src/library/utilities) add_subdirectory(src/library/optics) -add_subdirectory(src/library/RelativeOrbit) add_subdirectory(src/library/orbit) add_subdirectory(src/library/geodesy) @@ -153,7 +152,7 @@ endif() ## Linking libraries set(S2E_LIBRARIES - IGRF WRAPPER_NRLMSISE00 INIH SGP4 UTIL OPTICS RELATIVE_ORBIT_MODELS ORBIT_MODELS GEODESY MATH + IGRF WRAPPER_NRLMSISE00 INIH SGP4 UTIL OPTICS ORBIT_MODELS GEODESY MATH ) # Initialize link target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SC_IO RELATIVE_INFO ${S2E_LIBRARIES}) diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 48db2cf1a..8e7e91161 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -6,9 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ -#include - #include +#include #include #include diff --git a/src/library/RelativeOrbit/CMakeLists.txt b/src/library/RelativeOrbit/CMakeLists.txt deleted file mode 100644 index 73327571b..000000000 --- a/src/library/RelativeOrbit/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -project(RELATIVE_ORBIT_MODELS) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - RelativeOrbitModels.cpp -) - -include(../../../common.cmake) diff --git a/src/library/orbit/CMakeLists.txt b/src/library/orbit/CMakeLists.txt index 57db48492..f77d72d86 100644 --- a/src/library/orbit/CMakeLists.txt +++ b/src/library/orbit/CMakeLists.txt @@ -4,6 +4,7 @@ cmake_minimum_required(VERSION 3.10) add_library(${PROJECT_NAME} STATIC orbital_elements.cpp kepler_orbit.cpp + relative_orbit_models.cpp ) include(../../../common.cmake) diff --git a/src/library/RelativeOrbit/RelativeOrbitModels.cpp b/src/library/orbit/relative_orbit_models.cpp similarity index 97% rename from src/library/RelativeOrbit/RelativeOrbitModels.cpp rename to src/library/orbit/relative_orbit_models.cpp index 70e326310..07185cd0e 100644 --- a/src/library/RelativeOrbit/RelativeOrbitModels.cpp +++ b/src/library/orbit/relative_orbit_models.cpp @@ -1,8 +1,8 @@ /** - * @file RelativeOrbitModels.cpp + * @file relative_orbit_models.cpp * @brief Functions for relative orbit */ -#include "RelativeOrbitModels.h" +#include "relative_orbit_models.hpp" libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu) { libra::Matrix<6, 6> system_matrix; diff --git a/src/library/RelativeOrbit/RelativeOrbitModels.h b/src/library/orbit/relative_orbit_models.hpp similarity index 82% rename from src/library/RelativeOrbit/RelativeOrbitModels.h rename to src/library/orbit/relative_orbit_models.hpp index cca335685..d3091749d 100644 --- a/src/library/RelativeOrbit/RelativeOrbitModels.h +++ b/src/library/orbit/relative_orbit_models.hpp @@ -1,9 +1,11 @@ /** - * @file RelativeOrbitModels.h + * @file relative_orbit_models.hpp * @brief Functions for relative orbit */ -#pragma once +#ifndef S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ +#define S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ + #include "../math/Matrix.hpp" #include "../math/Vector.hpp" @@ -38,4 +40,6 @@ libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu); * @param [in] mu: Elapsed time [s] * @return State Transition Matrix */ -libra::Matrix<6, 6> CalculateHCWSTM(double orbit_radius, double mu, double elapsed_sec); \ No newline at end of file +libra::Matrix<6, 6> CalculateHCWSTM(double orbit_radius, double mu, double elapsed_sec); + +#endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ From 16576e18b5af9954eaeef4489667552a6932de5f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:02:46 +0100 Subject: [PATCH 0352/1086] Rename Constatns --- src/components/aocs/initialize_star_sensor.cpp | 2 +- src/components/aocs/initialize_sun_sensor.cpp | 2 +- src/components/aocs/reaction_wheel.cpp | 2 +- src/components/aocs/reaction_wheel_jitter.cpp | 2 +- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/sun_sensor.cpp | 2 +- .../communication/antenna_radiation_pattern.hpp | 2 +- .../communication/ground_station_calculator.cpp | 2 +- src/components/mission/initialize_telescope.cpp | 2 +- src/components/mission/telescope.cpp | 2 +- src/components/propulsion/initialize_simple_thruster.cpp | 2 +- src/components/propulsion/simple_thruster.cpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/environment/global/celestial_rotation.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 4 ++-- src/environment/global/hipparcos_catalogue.cpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- src/library/geodesy/geodetic_position.cpp | 2 +- src/library/math/Vector.cpp | 2 +- src/library/math/{Constant.hpp => constants.hpp} | 8 ++++---- src/library/math/s2e_math.cpp | 2 +- src/library/nrlmsise00/wrapper_nrlmsise00.cpp | 2 +- src/library/optics/gaussian_beam_base.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 2 +- 27 files changed, 31 insertions(+), 31 deletions(-) rename src/library/math/{Constant.hpp => constants.hpp} (92%) diff --git a/src/components/aocs/initialize_star_sensor.cpp b/src/components/aocs/initialize_star_sensor.cpp index 0c0b911ac..19466edd2 100644 --- a/src/components/aocs/initialize_star_sensor.cpp +++ b/src/components/aocs/initialize_star_sensor.cpp @@ -4,7 +4,7 @@ */ #include "initialize_star_sensor.hpp" -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/initialize_sun_sensor.cpp b/src/components/aocs/initialize_sun_sensor.cpp index bba6df4f5..130abe57e 100644 --- a/src/components/aocs/initialize_sun_sensor.cpp +++ b/src/components/aocs/initialize_sun_sensor.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/aocs/reaction_wheel.cpp b/src/components/aocs/reaction_wheel.cpp index ad0d262e6..1e7268748 100644 --- a/src/components/aocs/reaction_wheel.cpp +++ b/src/components/aocs/reaction_wheel.cpp @@ -4,7 +4,7 @@ */ #include "reaction_wheel.hpp" -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel_jitter.cpp b/src/components/aocs/reaction_wheel_jitter.cpp index 5a2bcced7..27a9a73a1 100644 --- a/src/components/aocs/reaction_wheel_jitter.cpp +++ b/src/components/aocs/reaction_wheel_jitter.cpp @@ -5,7 +5,7 @@ #include "reaction_wheel_jitter.hpp" -#include +#include #include RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index eb0963476..f9b0ed8ba 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index 4a4b01361..4e5f57d14 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -5,7 +5,7 @@ #include "sun_sensor.hpp" -#include +#include #include using libra::NormalRand; #include diff --git a/src/components/communication/antenna_radiation_pattern.hpp b/src/components/communication/antenna_radiation_pattern.hpp index 597922380..1e23f4e63 100644 --- a/src/components/communication/antenna_radiation_pattern.hpp +++ b/src/components/communication/antenna_radiation_pattern.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ #define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ -#include +#include #include #include diff --git a/src/components/communication/ground_station_calculator.cpp b/src/components/communication/ground_station_calculator.cpp index c32acc07e..1322ac3a5 100644 --- a/src/components/communication/ground_station_calculator.cpp +++ b/src/components/communication/ground_station_calculator.cpp @@ -5,7 +5,7 @@ #include "ground_station_calculator.hpp" -#include +#include #include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, diff --git a/src/components/mission/initialize_telescope.cpp b/src/components/mission/initialize_telescope.cpp index cb6228414..44dd1eeda 100644 --- a/src/components/mission/initialize_telescope.cpp +++ b/src/components/mission/initialize_telescope.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/mission/telescope.cpp b/src/components/mission/telescope.cpp index 077d0fb5b..df0d2d706 100644 --- a/src/components/mission/telescope.cpp +++ b/src/components/mission/telescope.cpp @@ -5,7 +5,7 @@ #include "telescope.hpp" -#include +#include #include using namespace std; diff --git a/src/components/propulsion/initialize_simple_thruster.cpp b/src/components/propulsion/initialize_simple_thruster.cpp index 41beaaae2..a7d3ca39b 100644 --- a/src/components/propulsion/initialize_simple_thruster.cpp +++ b/src/components/propulsion/initialize_simple_thruster.cpp @@ -4,7 +4,7 @@ */ #include "initialize_simple_thruster.hpp" -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/propulsion/simple_thruster.cpp index aaefc93c2..4d6d50911 100644 --- a/src/components/propulsion/simple_thruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include // Constructor diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index d236b6f73..5d0504599 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,7 +5,7 @@ #include "air_drag.hpp" -#include +#include #include #include #include diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 9f3e3b136..053648d05 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,7 +4,7 @@ */ #include "controlled_attitude.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 1d5446272..066a02eb0 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_ORBIT_H_ -#include +#include #include #include #include diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 68da09770..5a744b5b3 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -12,7 +12,7 @@ #include // for jday() #include // for gstime() -#include +#include #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 305685cef..895c0c9f8 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -8,7 +8,7 @@ #include //for jday() #include //for gstime() -#include +#include #include #include #include @@ -1052,7 +1052,7 @@ double GnssSatellites::AddIonosphericDelay(const int sat_id, const libra::Vector // sat_id is wrong or not validate if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return 0.0; - const double Earth_hemisphere = 6378.1; //[km] FIXME: Use Constant.hpp + const double Earth_hemisphere = 6378.1; //[km] FIXME: Use constants.hpp double altitude = 0.0; for (int i = 0; i < 3; ++i) altitude += pow(rec_position[i], 2.0); diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index beeb17daf..f375bcc74 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -4,7 +4,7 @@ */ #include "hipparcos_catalogue.hpp" -#include +#include #include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index c0baa604a..b42426194 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,7 +4,7 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include +#include #include #include #include diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 5dbf8f726..9b080cf8e 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -6,7 +6,7 @@ #include // TODO: do not to use the functions in SGP4 library -#include +#include #include #include diff --git a/src/library/math/Vector.cpp b/src/library/math/Vector.cpp index 9b3a7d360..3cade4ac1 100644 --- a/src/library/math/Vector.cpp +++ b/src/library/math/Vector.cpp @@ -5,7 +5,7 @@ #include "Vector.hpp" -#include "Constant.hpp" +#include "constants.hpp" namespace libra { Vector<3, double> ortho2spher(const Vector<3, double>& ortho) { diff --git a/src/library/math/Constant.hpp b/src/library/math/constants.hpp similarity index 92% rename from src/library/math/Constant.hpp rename to src/library/math/constants.hpp index 1094f4988..637b9ae5b 100644 --- a/src/library/math/Constant.hpp +++ b/src/library/math/constants.hpp @@ -1,10 +1,10 @@ /** - * @file + * @file constants.hpp * @brief header for math constant values */ -#ifndef CONSTANT_HPP_ -#define CONSTANT_HPP_ +#ifndef S2E_LIBRARY_MATH_CONSTANTS_H_ +#define S2E_LIBRARY_MATH_CONSTANTS_H_ #include // std::is_floating_point_v @@ -45,4 +45,4 @@ DEFINE_MATH_CONSTANT(arcsec_to_rad, deg_to_rad / 3600.0L) /* arcsecond to radian } // namespace libra -#endif // CONSTANT_HPP_ +#endif // S2E_LIBRARY_MATH_CONSTANTS_H_ diff --git a/src/library/math/s2e_math.cpp b/src/library/math/s2e_math.cpp index 472ba4520..df2108040 100644 --- a/src/library/math/s2e_math.cpp +++ b/src/library/math/s2e_math.cpp @@ -5,7 +5,7 @@ #include "s2e_math.hpp" -#include +#include namespace libra { double WrapTo2Pi(const double angle) { diff --git a/src/library/nrlmsise00/wrapper_nrlmsise00.cpp b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp index 9cf813a6b..b2c07f11f 100644 --- a/src/library/nrlmsise00/wrapper_nrlmsise00.cpp +++ b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp @@ -12,7 +12,7 @@ extern "C" { } #include /* for malloc/free */ -#include +#include #include #include #include /* maths functions */ diff --git a/src/library/optics/gaussian_beam_base.cpp b/src/library/optics/gaussian_beam_base.cpp index b70b64d2e..04500f54b 100644 --- a/src/library/optics/gaussian_beam_base.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -5,7 +5,7 @@ #include "gaussian_beam_base.hpp" -#include +#include #include GaussianBeamBase::GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt) diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 414b03a94..25c441905 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,7 +5,7 @@ #include "ground_station.hpp" -#include +#include #include #include #include diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 4742a3039..d57775b7d 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -5,7 +5,7 @@ #include "initialize_monte_carlo_parameters.hpp" -#include +#include using namespace std; From aeeb77ffb098db08d20a6a90104314eb4533ec36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:05:10 +0100 Subject: [PATCH 0353/1086] Rename GlobalRand --- src/components/aocs/gnss_receiver.cpp | 2 +- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/sun_sensor.cpp | 2 +- src/components/base_classes/sensor_base_tfs.hpp | 2 +- src/components/propulsion/simple_thruster.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/library/math/CMakeLists.txt | 2 +- src/library/math/RandomWalk_tfs.hpp | 2 +- .../math/{GlobalRand.cpp => global_randomization.cpp} | 4 ++-- .../math/{GlobalRand.h => global_randomization.hpp} | 11 ++++++----- 13 files changed, 19 insertions(+), 18 deletions(-) rename src/library/math/{GlobalRand.cpp => global_randomization.cpp} (84%) rename src/library/math/{GlobalRand.h => global_randomization.hpp} (78%) diff --git a/src/components/aocs/gnss_receiver.cpp b/src/components/aocs/gnss_receiver.cpp index 0bcfe476b..3015260f3 100644 --- a/src/components/aocs/gnss_receiver.cpp +++ b/src/components/aocs/gnss_receiver.cpp @@ -5,7 +5,7 @@ #include "gnss_receiver.hpp" -#include +#include #include #include diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 0b8f69998..15f31e696 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -5,7 +5,7 @@ #include "magnetorquer.hpp" -#include +#include #include #include diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index f9b0ed8ba..75f0d8a58 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -5,7 +5,7 @@ #include "star_sensor.hpp" -#include +#include #include #include diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index 4e5f57d14..c9a7c5224 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -8,7 +8,7 @@ #include #include using libra::NormalRand; -#include +#include #include diff --git a/src/components/base_classes/sensor_base_tfs.hpp b/src/components/base_classes/sensor_base_tfs.hpp index 960dfe487..2f0e03c4f 100644 --- a/src/components/base_classes/sensor_base_tfs.hpp +++ b/src/components/base_classes/sensor_base_tfs.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ #define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ -#include +#include template SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/propulsion/simple_thruster.cpp index 4d6d50911..b3846e877 100644 --- a/src/components/propulsion/simple_thruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -4,7 +4,7 @@ */ #include "simple_thruster.hpp" -#include +#include #include #include diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 92cc68171..46873f394 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,7 +9,7 @@ using libra::NormalRand; #include -#include "../library/math/GlobalRand.h" +#include "../library/math/global_randomization.hpp" #include "../library/math/RandomWalk.hpp" #include "../interface/log_output/log_utility.hpp" diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index ea3b6464b..030d8eddf 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,7 +5,7 @@ #include "atmosphere.hpp" -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index b927a6998..e171c0fd1 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -6,7 +6,7 @@ #include "geomagnetic_field.hpp" #include -#include +#include #include #include diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index dff672949..a38417f77 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -2,7 +2,7 @@ project(MATH) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - GlobalRand.cpp + global_randomization.cpp NormalRand.cpp Quantization.cpp Quaternion.cpp diff --git a/src/library/math/RandomWalk_tfs.hpp b/src/library/math/RandomWalk_tfs.hpp index 8e1266c4d..4682daf6e 100644 --- a/src/library/math/RandomWalk_tfs.hpp +++ b/src/library/math/RandomWalk_tfs.hpp @@ -5,7 +5,7 @@ #pragma once -#include +#include #include diff --git a/src/library/math/GlobalRand.cpp b/src/library/math/global_randomization.cpp similarity index 84% rename from src/library/math/GlobalRand.cpp rename to src/library/math/global_randomization.cpp index c5d5bb88e..30fe34d32 100644 --- a/src/library/math/GlobalRand.cpp +++ b/src/library/math/global_randomization.cpp @@ -1,9 +1,9 @@ /** - * @class GlobalRand.cpp + * @class global_randomization.cpp * @brief Class to manage global randomization */ -#include "GlobalRand.h" +#include "global_randomization.hpp" GlobalRand g_rand; diff --git a/src/library/math/GlobalRand.h b/src/library/math/global_randomization.hpp similarity index 78% rename from src/library/math/GlobalRand.h rename to src/library/math/global_randomization.hpp index a16322bc0..55b7c7784 100644 --- a/src/library/math/GlobalRand.h +++ b/src/library/math/global_randomization.hpp @@ -1,14 +1,15 @@ /** - * @file GlobalRand.h + * @file global_randomization.hpp * @brief Class to manage global randomization */ -#ifndef GLOBALRAND_HPP_ -#define GLOBALRAND_HPP_ +#ifndef S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ +#define S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ + #include "./Ran0.hpp" /** - * @class GlobalRand.h + * @class global_randomization.hpp * @brief Class to manage global randomization * @note Used to make randomized seed for other randomization */ @@ -38,4 +39,4 @@ class GlobalRand { extern GlobalRand g_rand; //!< Global randomization -#endif \ No newline at end of file +#endif // S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ From d31757a3fc384e9b9044d8618551da606f0e7c4c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:08:44 +0100 Subject: [PATCH 0354/1086] Rename Matrix --- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/star_sensor.cpp | 2 +- src/components/base_classes/sensor_base.hpp | 2 +- .../communication/ground_station_calculator.hpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/library/geodesy/geodetic_position.cpp | 2 +- src/library/math/MatVec.hpp | 2 +- src/library/math/Quaternion.hpp | 2 +- src/library/math/{Matrix.hpp => matrix.hpp} | 12 ++++++------ src/library/math/{Matrix_ifs.hpp => matrix_ifs.hpp} | 2 +- src/library/math/{Matrix_tfs.hpp => matrix_tfs.hpp} | 2 +- src/library/orbit/kepler_orbit.hpp | 2 +- src/library/orbit/relative_orbit_models.hpp | 2 +- .../spacecraft/structure/kinematics_parameters.hpp | 2 +- 18 files changed, 23 insertions(+), 23 deletions(-) rename src/library/math/{Matrix.hpp => matrix.hpp} (96%) rename src/library/math/{Matrix_ifs.hpp => matrix_ifs.hpp} (98%) rename src/library/math/{Matrix_tfs.hpp => matrix_tfs.hpp} (99%) diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 4d3c8237a..b595d258a 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ #define S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ -#include +#include #include #include #include diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 75f0d8a58..467a8437c 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index d1b9d14f8..f08dcb62a 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ #define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ -#include +#include #include #include #include diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index c6664e915..a9b58a1f3 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -8,7 +8,7 @@ #define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ #include -#include +#include #include #include #include diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index f145de03a..b6e83c24e 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -9,7 +9,7 @@ #include #include "../library/math/MatVec.hpp" -#include "../library/math/Matrix.hpp" +#include "../library/math/matrix.hpp" #include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 481445cad..58b9c2ff3 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -9,7 +9,7 @@ #include #include "../library/math/MatVec.hpp" -#include "../library/math/Matrix.hpp" +#include "../library/math/matrix.hpp" #include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" #include "simple_disturbance.hpp" diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 066a02eb0..abac686bf 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 5e4be35f3..ee5f31be3 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -11,7 +11,7 @@ #include #include "library/math/MatVec.hpp" -#include "library/math/Matrix.hpp" +#include "library/math/matrix.hpp" #include "library/math/Quaternion.hpp" #include "library/math/Vector.hpp" #include "celestial_rotation.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 4058db893..bab4a5727 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -11,7 +11,7 @@ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #include -#include +#include #include #include #include diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 9b080cf8e..052b086e3 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -7,7 +7,7 @@ #include // TODO: do not to use the functions in SGP4 library #include -#include +#include #include GeodeticPosition::GeodeticPosition() { diff --git a/src/library/math/MatVec.hpp b/src/library/math/MatVec.hpp index 89e4ed754..6f894e0c8 100644 --- a/src/library/math/MatVec.hpp +++ b/src/library/math/MatVec.hpp @@ -6,7 +6,7 @@ #ifndef MAT_VEC_HPP_ #define MAT_VEC_HPP_ -#include "Matrix.hpp" +#include "matrix.hpp" #include "Vector.hpp" namespace libra { diff --git a/src/library/math/Quaternion.hpp b/src/library/math/Quaternion.hpp index 1f51a73ff..b808f3e3f 100644 --- a/src/library/math/Quaternion.hpp +++ b/src/library/math/Quaternion.hpp @@ -6,7 +6,7 @@ #ifndef QUATERNION_HPP_ #define QUATERNION_HPP_ -#include "Matrix.hpp" +#include "matrix.hpp" #include "Vector.hpp" namespace libra { diff --git a/src/library/math/Matrix.hpp b/src/library/math/matrix.hpp similarity index 96% rename from src/library/math/Matrix.hpp rename to src/library/math/matrix.hpp index cf30845c4..0dd5417cf 100644 --- a/src/library/math/Matrix.hpp +++ b/src/library/math/matrix.hpp @@ -1,10 +1,10 @@ /** - * @file Matrix.hpp + * @file matrix.hpp * @brief Matrix class to handle math matrix with template */ -#ifndef MATRIX_HPP_ -#define MATRIX_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_H_ +#define S2E_LIBRARY_MATH_MATRIX_H_ #include // for size_t #include // for ostream, cout @@ -253,7 +253,7 @@ Matrix rotz(const double& theta); } // namespace libra -#include "Matrix_ifs.hpp" // inline function definisions. -#include "Matrix_tfs.hpp" // template function definisions. +#include "matrix_ifs.hpp" // inline function definisions. +#include "matrix_tfs.hpp" // template function definisions. -#endif // MATRIX_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_H_ diff --git a/src/library/math/Matrix_ifs.hpp b/src/library/math/matrix_ifs.hpp similarity index 98% rename from src/library/math/Matrix_ifs.hpp rename to src/library/math/matrix_ifs.hpp index b68e0c1a5..d14802b4a 100644 --- a/src/library/math/Matrix_ifs.hpp +++ b/src/library/math/matrix_ifs.hpp @@ -1,5 +1,5 @@ /** - * @file Matrix_ifs.hpp + * @file matrix_ifs.hpp * @brief Matrix class to handle math matrix with template */ diff --git a/src/library/math/Matrix_tfs.hpp b/src/library/math/matrix_tfs.hpp similarity index 99% rename from src/library/math/Matrix_tfs.hpp rename to src/library/math/matrix_tfs.hpp index ccb9cf433..f51676dcb 100644 --- a/src/library/math/Matrix_tfs.hpp +++ b/src/library/math/matrix_tfs.hpp @@ -1,5 +1,5 @@ /** - * @file Matrix_tfs.hpp + * @file matrix_tfs.hpp * @brief Matrix class to handle math matrix with template */ diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 4bffa5647..0a8522a51 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ #define S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ -#include "../math/Matrix.hpp" +#include "../math/matrix.hpp" #include "../math/Vector.hpp" #include "./orbital_elements.hpp" diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index d3091749d..90acb2433 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ #define S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ -#include "../math/Matrix.hpp" +#include "../math/matrix.hpp" #include "../math/Vector.hpp" /** diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 7f133e238..04bcb0f85 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ -#include +#include #include using libra::Matrix; using libra::Vector; From 9ac05eb93616c5ae6457a2cdfe7fc926bc3a5389 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:12:57 +0100 Subject: [PATCH 0355/1086] Rename MatVec --- src/components/aocs/magnetorquer.cpp | 2 +- .../communication/ground_station_calculator.hpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/interface/log_output/log_utility.hpp | 2 +- src/library/math/matrix_ifs.hpp | 6 +++--- src/library/math/matrix_tfs.hpp | 6 +++--- src/library/math/{MatVec.hpp => matrix_vector.hpp} | 12 ++++++------ .../math/{MatVec_impl.hpp => matrix_vector_impl.hpp} | 10 ++++++---- src/library/orbit/kepler_orbit.cpp | 2 +- 14 files changed, 28 insertions(+), 26 deletions(-) rename src/library/math/{MatVec.hpp => matrix_vector.hpp} (87%) rename src/library/math/{MatVec_impl.hpp => matrix_vector_impl.hpp} (94%) diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 15f31e696..53353f13b 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include #include diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index a9b58a1f3..475135f4d 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -7,7 +7,7 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ #define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ -#include +#include #include #include #include diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index b6e83c24e..69e98ab42 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,7 +8,7 @@ #include -#include "../library/math/MatVec.hpp" +#include "../library/math/matrix_vector.hpp" #include "../library/math/matrix.hpp" #include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 58b9c2ff3..19f12877a 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,7 +8,7 @@ #include -#include "../library/math/MatVec.hpp" +#include "../library/math/matrix_vector.hpp" #include "../library/math/matrix.hpp" #include "../library/math/Vector.hpp" #include "../interface/log_output/loggable.hpp" diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index d4c6c7ce8..f9122c15e 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#include +#include #include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index abac686bf..5eef42a42 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -7,7 +7,7 @@ #define S2E_DYNAMICS_ORBIT_ORBIT_H_ #include -#include +#include #include #include #include diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index ee5f31be3..31c9569d5 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,7 +10,7 @@ #include #include -#include "library/math/MatVec.hpp" +#include "library/math/matrix_vector.hpp" #include "library/math/matrix.hpp" #include "library/math/Quaternion.hpp" #include "library/math/Vector.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index bab4a5727..bd2b86cd4 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,7 +10,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#include +#include #include #include #include diff --git a/src/interface/log_output/log_utility.hpp b/src/interface/log_output/log_utility.hpp index 95e6d3a82..d2a00eb35 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/interface/log_output/log_utility.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ #define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ -#include +#include #include #include #include diff --git a/src/library/math/matrix_ifs.hpp b/src/library/math/matrix_ifs.hpp index d14802b4a..b3856a38b 100644 --- a/src/library/math/matrix_ifs.hpp +++ b/src/library/math/matrix_ifs.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef MATRIX_IFS_HPP_ -#define MATRIX_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_IFS_H_ +#define S2E_LIBRARY_MATH_MATRIX_IFS_H_ #include // for invalid_argument @@ -56,4 +56,4 @@ bool Matrix::is_valid_range_(size_t row, size_t column) { } // namespace libra -#endif // MATRIX_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_IFS_H_ diff --git a/src/library/math/matrix_tfs.hpp b/src/library/math/matrix_tfs.hpp index f51676dcb..a61283993 100644 --- a/src/library/math/matrix_tfs.hpp +++ b/src/library/math/matrix_tfs.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef MATRIX_TFS_HPP_ -#define MATRIX_TFS_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_TFS_H_ +#define S2E_LIBRARY_MATH_MATRIX_TFS_H_ #include #include // for cout @@ -192,4 +192,4 @@ Matrix rotz(const double& theta) { } // namespace libra -#endif // MATRIX_TFS_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_TFS_H_ diff --git a/src/library/math/MatVec.hpp b/src/library/math/matrix_vector.hpp similarity index 87% rename from src/library/math/MatVec.hpp rename to src/library/math/matrix_vector.hpp index 6f894e0c8..d082b7e2b 100644 --- a/src/library/math/MatVec.hpp +++ b/src/library/math/matrix_vector.hpp @@ -1,13 +1,13 @@ /** - * @file MatVec.hpp + * @file matrix_vector.hpp * @brief Template library for Matrix-Vector calculation */ -#ifndef MAT_VEC_HPP_ -#define MAT_VEC_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_H_ +#define S2E_LIBRARY_MATH_MATRIX_VECTOR_H_P -#include "matrix.hpp" #include "Vector.hpp" +#include "matrix.hpp" namespace libra { @@ -54,6 +54,6 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& } // namespace libra -#include "MatVec_impl.hpp" +#include "matrix_vector_impl.hpp" -#endif // MAT_VEC_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_H_ diff --git a/src/library/math/MatVec_impl.hpp b/src/library/math/matrix_vector_impl.hpp similarity index 94% rename from src/library/math/MatVec_impl.hpp rename to src/library/math/matrix_vector_impl.hpp index c4877ed88..202fc4023 100644 --- a/src/library/math/MatVec_impl.hpp +++ b/src/library/math/matrix_vector_impl.hpp @@ -1,10 +1,11 @@ /** - * @file MatVec_impl.hpp + * @file matrix_vector_impl.hpp * @brief Template library for Matrix-Vector calculation */ -#ifndef MAT_VEC_IMPL_HPP_ -#define MAT_VEC_IMPL_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ +#define S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ + #include // for invalid_argument. namespace libra { @@ -139,4 +140,5 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& } } // namespace libra -#endif + +#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ diff --git a/src/library/orbit/kepler_orbit.cpp b/src/library/orbit/kepler_orbit.cpp index f9e33d34f..bf09bf02c 100644 --- a/src/library/orbit/kepler_orbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -4,7 +4,7 @@ */ #include "kepler_orbit.hpp" -#include "../math/MatVec.hpp" +#include "../math/matrix_vector.hpp" #include "../math/s2e_math.hpp" KeplerOrbit::KeplerOrbit() {} From 42fc1a04e820da5493e742396bb6d66256b631b8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:16:32 +0100 Subject: [PATCH 0356/1086] Rename NormalRand --- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.cpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- src/components/base_classes/sensor_base.hpp | 2 +- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/library/math/CMakeLists.txt | 2 +- src/library/math/RandomWalk.hpp | 2 +- .../math/{NormalRand.cpp => normal_randomization.cpp} | 4 ++-- .../math/{NormalRand.hpp => normal_randomization.hpp} | 11 ++++++----- ...ormalRand_ifs.hpp => normal_randomization_ifs.hpp} | 8 ++++---- .../sample_spacecraft/sample_spacecraft.cpp | 2 +- 18 files changed, 27 insertions(+), 26 deletions(-) rename src/library/math/{NormalRand.cpp => normal_randomization.cpp} (93%) rename src/library/math/{NormalRand.hpp => normal_randomization.hpp} (90%) rename src/library/math/{NormalRand_ifs.hpp => normal_randomization_ifs.hpp} (75%) diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index acaa14603..7b668f6ee 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ #define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ -#include +#include #include #include #include diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index b595d258a..31aa0a2dc 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ #include -#include +#include #include #include #include diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 75f9313dd..8eece240c 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ #define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ -#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index c9a7c5224..087ee10dc 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -6,7 +6,7 @@ #include "sun_sensor.hpp" #include -#include +#include using libra::NormalRand; #include diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 18785c170..99c9441e3 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ #define S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ -#include +#include #include #include #include diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index f08dcb62a..7fa7bde29 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ #include -#include +#include #include #include diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index 3d5875c82..96c4e3e90 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ -#include +#include #include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 5cf925442..75f81466c 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ -#include +#include #include #include #include diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 2d9a1e062..7e8f18e78 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ #define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ -#include +#include #include #include #include diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 46873f394..aa230d048 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -5,7 +5,7 @@ #include "magnetic_disturbance.hpp" -#include "../library/math/NormalRand.hpp" +#include "../library/math/normal_randomization.hpp" using libra::NormalRand; #include diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 030d8eddf..392b62ea8 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index e171c0fd1..d8f0a60f1 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index a38417f77..069b958ed 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC global_randomization.cpp - NormalRand.cpp + normal_randomization.cpp Quantization.cpp Quaternion.cpp Ran0.cpp diff --git a/src/library/math/RandomWalk.hpp b/src/library/math/RandomWalk.hpp index 8e8020f85..8a852127e 100644 --- a/src/library/math/RandomWalk.hpp +++ b/src/library/math/RandomWalk.hpp @@ -5,7 +5,7 @@ #pragma once -#include "./NormalRand.hpp" +#include "./normal_randomization.hpp" #include "./ODE.hpp" #include "./Vector.hpp" diff --git a/src/library/math/NormalRand.cpp b/src/library/math/normal_randomization.cpp similarity index 93% rename from src/library/math/NormalRand.cpp rename to src/library/math/normal_randomization.cpp index 2165e0cd3..0cc15aa61 100644 --- a/src/library/math/NormalRand.cpp +++ b/src/library/math/normal_randomization.cpp @@ -1,9 +1,9 @@ /** - * @file NormalRand.cpp + * @file normal_randomization.cpp * @brief Class to generate random value with normal distribution with Box-Muller method * @note Ref: NUMERICAL RECIPES in C, p.216-p.217 */ -#include "NormalRand.hpp" +#include "normal_randomization.hpp" using libra::NormalRand; #include //DBL_EPSILON diff --git a/src/library/math/NormalRand.hpp b/src/library/math/normal_randomization.hpp similarity index 90% rename from src/library/math/NormalRand.hpp rename to src/library/math/normal_randomization.hpp index 28e829e6c..6d39b1223 100644 --- a/src/library/math/NormalRand.hpp +++ b/src/library/math/normal_randomization.hpp @@ -1,10 +1,11 @@ /** - * @file NormalRand.hpp + * @file normal_randomization.hpp * @brief Class to generate random value with normal distribution with Box-Muller method * @note Ref: NUMERICAL RECIPES in C, p.216-p.217 */ -#ifndef NORMAL_RAND_HPP_ -#define NORMAL_RAND_HPP_ + +#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ +#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ #include "Ran1.hpp" using libra::Ran1; @@ -100,6 +101,6 @@ class NormalRand { } // namespace libra -#include "NormalRand_ifs.hpp" // inline function definisions. +#include "normal_randomization_ifs.hpp" // inline function definisions. -#endif // NORMAL_RAND_HPP_ +#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ diff --git a/src/library/math/NormalRand_ifs.hpp b/src/library/math/normal_randomization_ifs.hpp similarity index 75% rename from src/library/math/NormalRand_ifs.hpp rename to src/library/math/normal_randomization_ifs.hpp index 39851e42f..29b5492d4 100644 --- a/src/library/math/NormalRand_ifs.hpp +++ b/src/library/math/normal_randomization_ifs.hpp @@ -1,10 +1,10 @@ /** - * @file NormalRand_ifs.hpp + * @file normal_randomization_ifs.hpp * @brief Class to generate random value with normal distribution with Box-Muller method * @note Inline functions */ -#ifndef NORMAL_RAND_IFS_HPP_ -#define NORMAL_RAND_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ +#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ namespace libra { @@ -29,4 +29,4 @@ void NormalRand::set_param(double avg, double stddev, long seed) { } // namespace libra -#endif // NORMAL_RAND_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 46d554db9..fbdd5af09 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,7 +5,7 @@ #include "sample_spacecraft.hpp" -#include +#include #include #include "sample_components.hpp" From 7c5400871ff20b835dc3801100466bad64910544 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:22:02 +0100 Subject: [PATCH 0357/1086] Rename ODE --- src/components/aocs/reaction_wheel_ode.hpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.hpp | 2 +- src/dynamics/orbit/relative_orbit.hpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 2 +- src/library/math/RandomWalk.hpp | 2 +- .../{ODE.hpp => ordinary_differential_equation.hpp} | 13 +++++++------ ...s.hpp => ordinary_differential_equation_ifs.hpp} | 8 ++++---- ....hpp => ordinary_differential_equation_impl.hpp} | 7 ++++++- ...s.hpp => ordinary_differential_equation_tfs.hpp} | 8 ++++---- 9 files changed, 26 insertions(+), 20 deletions(-) rename src/library/math/{ODE.hpp => ordinary_differential_equation.hpp} (85%) rename src/library/math/{ODE_ifs.hpp => ordinary_differential_equation_ifs.hpp} (72%) rename src/library/math/{ODE_impl.hpp => ordinary_differential_equation_impl.hpp} (81%) rename src/library/math/{ODE_tfs.hpp => ordinary_differential_equation_tfs.hpp} (83%) diff --git a/src/components/aocs/reaction_wheel_ode.hpp b/src/components/aocs/reaction_wheel_ode.hpp index 1ba573640..d03657f98 100644 --- a/src/components/aocs/reaction_wheel_ode.hpp +++ b/src/components/aocs/reaction_wheel_ode.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ -#include +#include #include #include diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 86217d3e8..100447717 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -7,7 +7,7 @@ #define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ #include "../../library/orbit/kepler_orbit.hpp" -#include "../../library/math/ODE.hpp" +#include "../../library/math/ordinary_differential_equation.hpp" #include "orbit.hpp" /** diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 8e7e91161..f2cd0a562 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ #define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ -#include +#include #include #include #include diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 512885906..eee6fcc31 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ #define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ -#include +#include #include #include "orbit.hpp" diff --git a/src/library/math/RandomWalk.hpp b/src/library/math/RandomWalk.hpp index 8a852127e..8c1aaafe5 100644 --- a/src/library/math/RandomWalk.hpp +++ b/src/library/math/RandomWalk.hpp @@ -6,7 +6,7 @@ #pragma once #include "./normal_randomization.hpp" -#include "./ODE.hpp" +#include "./ordinary_differential_equation.hpp" #include "./Vector.hpp" /** diff --git a/src/library/math/ODE.hpp b/src/library/math/ordinary_differential_equation.hpp similarity index 85% rename from src/library/math/ODE.hpp rename to src/library/math/ordinary_differential_equation.hpp index 81e988a37..8c979842b 100644 --- a/src/library/math/ODE.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -1,9 +1,10 @@ /** - * @file ODE.hpp + * @file ordinary_differential_equation.hpp * @brief Class for Ordinary Difference Equation */ -#ifndef ODE_HPP_ -#define ODE_HPP_ + +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ #include "./Vector.hpp" @@ -110,7 +111,7 @@ class ODE { } // namespace libra -#include "./ODE_ifs.hpp" // inline function definisions. -#include "./ODE_tfs.hpp" // template function definisions. +#include "./ordinary_differential_equation_ifs.hpp" // inline function definisions. +#include "./ordinary_differential_equation_tfs.hpp" // template function definisions. -#endif // ODE_HPP_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ diff --git a/src/library/math/ODE_ifs.hpp b/src/library/math/ordinary_differential_equation_ifs.hpp similarity index 72% rename from src/library/math/ODE_ifs.hpp rename to src/library/math/ordinary_differential_equation_ifs.hpp index a14953122..3fe09c945 100644 --- a/src/library/math/ODE_ifs.hpp +++ b/src/library/math/ordinary_differential_equation_ifs.hpp @@ -1,10 +1,10 @@ /** - * @file ODE_ifs.hpp + * @file ordinary_differential_equation_ifs.hpp * @brief Class for Ordinary Difference Equation (inline functions) */ -#ifndef ODE_IFS_HPP_ -#define ODE_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ namespace libra { @@ -43,4 +43,4 @@ libra::Vector& ODE::state() { } // namespace libra -#endif // ODE_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ diff --git a/src/library/math/ODE_impl.hpp b/src/library/math/ordinary_differential_equation_impl.hpp similarity index 81% rename from src/library/math/ODE_impl.hpp rename to src/library/math/ordinary_differential_equation_impl.hpp index f1c4656c0..829f1fd57 100644 --- a/src/library/math/ODE_impl.hpp +++ b/src/library/math/ordinary_differential_equation_impl.hpp @@ -1,9 +1,12 @@ /*! /** - * @file ODE_impl.hpp + * @file ordinary_differential_equation_impl.hpp * @brief Class for Ordinary Difference Equation */ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ + namespace libra { template @@ -39,3 +42,5 @@ ODE& ODE::operator++() { } } // namespace libra + +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ diff --git a/src/library/math/ODE_tfs.hpp b/src/library/math/ordinary_differential_equation_tfs.hpp similarity index 83% rename from src/library/math/ODE_tfs.hpp rename to src/library/math/ordinary_differential_equation_tfs.hpp index be02b5946..ec56dd0f6 100644 --- a/src/library/math/ODE_tfs.hpp +++ b/src/library/math/ordinary_differential_equation_tfs.hpp @@ -1,9 +1,9 @@ /** - * @file ODE_tfs.hpp + * @file ordinary_differential_equation_tfs.hpp * @brief Class for Ordinary Difference Equation (template functions) */ -#ifndef ODE_TFS_HPP_ -#define ODE_TFS_HPP_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ namespace libra { @@ -49,4 +49,4 @@ void ODE::setStepWidth(double new_step) { } } // namespace libra -#endif // ODE_TFS_HPP_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ From 5c85f2e7997c24c75bb53f5998c0407b383d0498 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:24:05 +0100 Subject: [PATCH 0358/1086] Rename Quantization --- src/library/math/CMakeLists.txt | 2 +- src/library/math/{Quantization.cpp => quantization.cpp} | 4 ++-- src/library/math/{Quantization.h => quantization.hpp} | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) rename src/library/math/{Quantization.cpp => quantization.cpp} (86%) rename src/library/math/{Quantization.h => quantization.hpp} (80%) diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index 069b958ed..b127a0058 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC global_randomization.cpp normal_randomization.cpp - Quantization.cpp + quantization.cpp Quaternion.cpp Ran0.cpp Ran1.cpp diff --git a/src/library/math/Quantization.cpp b/src/library/math/quantization.cpp similarity index 86% rename from src/library/math/Quantization.cpp rename to src/library/math/quantization.cpp index be716c359..d75633ff6 100644 --- a/src/library/math/Quantization.cpp +++ b/src/library/math/quantization.cpp @@ -1,9 +1,9 @@ /** - * @file Quantization.cpp + * @file quantization.cpp * @brief Functions for quantization */ -#include "Quantization.h" +#include "quantization.hpp" double quantization(double continuous_num, double resolution) { int bin_num = (int)((double)continuous_num / resolution); diff --git a/src/library/math/Quantization.h b/src/library/math/quantization.hpp similarity index 80% rename from src/library/math/Quantization.h rename to src/library/math/quantization.hpp index 2abf12de8..a47abea09 100644 --- a/src/library/math/Quantization.h +++ b/src/library/math/quantization.hpp @@ -1,10 +1,10 @@ /** - * @file Quantization.h + * @file quantization.hpp * @brief Functions for quantization */ -#ifndef QUANTIZATION_H_ -#define QUANTIZATION_H_ +#ifndef S2E_LIBRARY_MATH_QUANTIZATION_H_ +#define S2E_LIBRARY_MATH_QUANTIZATION_H_ /** * @fn quantization @@ -24,4 +24,4 @@ double quantization(double continuous_num, double resolution); */ float quantization_f(double continuous_num, double resolution); -#endif // QUANTIZATION_H_ +#endif // S2E_LIBRARY_MATH_QUANTIZATION_H_ From 4de09b61bef4bc490b016c4d256b7c71b5403477 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:26:36 +0100 Subject: [PATCH 0359/1086] Rename Quaternion --- CMakeLists.txt | 2 +- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.cpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel_jitter.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- src/components/communication/antenna.hpp | 2 +- src/components/mission/telescope.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/surface_force.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- src/interface/initialize/initialize_file_access.hpp | 2 +- src/interface/log_output/log_utility.hpp | 2 +- src/library/geodesy/geodetic_position.hpp | 2 +- src/library/math/CMakeLists.txt | 2 +- src/library/math/TestQuaternion.cpp | 4 ++-- src/library/math/{Quaternion.cpp => quaternion.cpp} | 4 ++-- src/library/math/{Quaternion.hpp => quaternion.hpp} | 12 ++++++------ .../math/{Quaternion_ifs.hpp => quaternion_ifs.hpp} | 8 ++++---- .../initialize_monte_carlo_parameters.hpp | 2 +- .../monte_carlo_simulation/simulation_object.hpp | 2 +- 32 files changed, 42 insertions(+), 42 deletions(-) rename src/library/math/{Quaternion.cpp => quaternion.cpp} (99%) rename src/library/math/{Quaternion.hpp => quaternion.hpp} (96%) rename src/library/math/{Quaternion_ifs.hpp => quaternion_ifs.hpp} (77%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2a35cbf0a..7f6b9cb9e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -211,7 +211,7 @@ if(GOOGLE_TEST) # Unit test set(TEST_PROJECT_NAME ${PROJECT_NAME}_TEST) set(TEST_FILES - src/library/math/TestQuaternion.cpp + src/library/math/Testquaternion.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 7b668f6ee..91eb95dad 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ #include -#include +#include #include #include #include diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index bdce733bc..a51966f70 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ #define S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ -#include +#include #include #include diff --git a/src/components/aocs/magnetometer.cpp b/src/components/aocs/magnetometer.cpp index ecee8e731..f239eac5d 100644 --- a/src/components/aocs/magnetometer.cpp +++ b/src/components/aocs/magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "magnetometer.hpp" -#include +#include MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const MagEnvironment* magnet) diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 56c7f908d..9aef3ca26 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ #define S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ -#include +#include #include #include diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 53353f13b..f622d65e0 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 31aa0a2dc..c8909adf3 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel_jitter.hpp b/src/components/aocs/reaction_wheel_jitter.hpp index fc8fbf499..9eae459d3 100644 --- a/src/components/aocs/reaction_wheel_jitter.hpp +++ b/src/components/aocs/reaction_wheel_jitter.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ #pragma once -#include +#include #include #include diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 8eece240c..e230c580d 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ #include -#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 99c9441e3..286b0b60c 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ #include -#include +#include #include #include #include diff --git a/src/components/communication/antenna.hpp b/src/components/communication/antenna.hpp index a0cae1720..a7eb89c95 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ #define S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ -#include +#include #include using libra::Quaternion; using libra::Vector; diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 9289133c1..9b9ffdf34 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_MISSION_TELESCOPE_H_ #define S2E_COMPONENTS_MISSION_TELESCOPE_H_ -#include +#include #include #include #include diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 7e8f18e78..cb49ac1d8 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ #include -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 17ff15ea6..ce3945de8 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,7 +9,7 @@ #include #include -#include "../library/math/Quaternion.hpp" +#include "../library/math/quaternion.hpp" #include "../library/math/Vector.hpp" #include "../environment/local/atmosphere.hpp" #include "../interface/log_output/loggable.hpp" diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 27166227a..5c382684f 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -8,7 +8,7 @@ #ifndef S2E_DISTURBANCES_SURFACE_FORCE_H_ #define S2E_DISTURBANCES_SURFACE_FORCE_H_ -#include "../library/math/Quaternion.hpp" +#include "../library/math/quaternion.hpp" #include "../library/math/Vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" #include "simple_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index f9122c15e..6f133f6d9 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -7,7 +7,7 @@ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ #include -#include +#include #include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 5eef42a42..5607a9855 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include using libra::Matrix; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 31c9569d5..942359e1c 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -12,7 +12,7 @@ #include "library/math/matrix_vector.hpp" #include "library/math/matrix.hpp" -#include "library/math/Quaternion.hpp" +#include "library/math/quaternion.hpp" #include "library/math/Vector.hpp" #include "celestial_rotation.hpp" #include "interface/log_output/loggable.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index bd2b86cd4..d7da4e382 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -12,7 +12,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index f36c81825..0f699d366 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#include +#include #include #include #include diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 6cdaddf12..49c36a1d5 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -9,7 +9,7 @@ #include -#include +#include #include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index cc4420f50..dcc397fda 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -8,7 +8,7 @@ #include using libra::Vector; -#include +#include using libra::Quaternion; #include diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index 20666f50a..d781a8aff 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -15,7 +15,7 @@ #else #include #endif -#include +#include #include #include #include diff --git a/src/interface/log_output/log_utility.hpp b/src/interface/log_output/log_utility.hpp index d2a00eb35..39354a66d 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/interface/log_output/log_utility.hpp @@ -7,7 +7,7 @@ #define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ #include -#include +#include #include #include #include diff --git a/src/library/geodesy/geodetic_position.hpp b/src/library/geodesy/geodetic_position.hpp index e545431e5..1eeb897ae 100644 --- a/src/library/geodesy/geodetic_position.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ #define S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ -#include +#include #include /** diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index b127a0058..1675ffdf1 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC global_randomization.cpp normal_randomization.cpp quantization.cpp - Quaternion.cpp + quaternion.cpp Ran0.cpp Ran1.cpp Vector.cpp diff --git a/src/library/math/TestQuaternion.cpp b/src/library/math/TestQuaternion.cpp index 79c8b7a23..438280c49 100644 --- a/src/library/math/TestQuaternion.cpp +++ b/src/library/math/TestQuaternion.cpp @@ -1,10 +1,10 @@ /** - * @file TestQuaternion.cpp + * @file Testquaternion.cpp * @brief Test codes for Quaternion class with GoogleTest */ #include -#include "Quaternion.hpp" +#include "quaternion.hpp" TEST(Quaternion, ConstructorFourNumber) { libra::Quaternion q(0.5, 0.5, 0.5, 0.5); diff --git a/src/library/math/Quaternion.cpp b/src/library/math/quaternion.cpp similarity index 99% rename from src/library/math/Quaternion.cpp rename to src/library/math/quaternion.cpp index fcc18390f..345132115 100644 --- a/src/library/math/Quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -1,9 +1,9 @@ /** - * @file Quaternion.hpp + * @file quaternion.hpp * @brief Class for Quaternion */ -#include "Quaternion.hpp" +#include "quaternion.hpp" #include #include diff --git a/src/library/math/Quaternion.hpp b/src/library/math/quaternion.hpp similarity index 96% rename from src/library/math/Quaternion.hpp rename to src/library/math/quaternion.hpp index b808f3e3f..635560716 100644 --- a/src/library/math/Quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -1,13 +1,13 @@ /** - * @file Quaternion.hpp + * @file quaternion.hpp * @brief Class for Quaternion */ -#ifndef QUATERNION_HPP_ -#define QUATERNION_HPP_ +#ifndef S2E_LIBRARY_MATH_QUATERNION_H_ +#define S2E_LIBRARY_MATH_QUATERNION_H_ -#include "matrix.hpp" #include "Vector.hpp" +#include "matrix.hpp" namespace libra { @@ -207,6 +207,6 @@ Quaternion operator*(const Quaternion& lhs, const Vector<3>& rhs); Quaternion operator*(const double& lhs, const Quaternion& rhs); } // namespace libra -#include "Quaternion_ifs.hpp" // inline function definisions. +#include "quaternion_ifs.hpp" // inline function definisions. -#endif // QUATERNION_HPP_ +#endif // S2E_LIBRARY_MATH_QUATERNION_H_ diff --git a/src/library/math/Quaternion_ifs.hpp b/src/library/math/quaternion_ifs.hpp similarity index 77% rename from src/library/math/Quaternion_ifs.hpp rename to src/library/math/quaternion_ifs.hpp index 9de3ec451..65689d5d7 100644 --- a/src/library/math/Quaternion_ifs.hpp +++ b/src/library/math/quaternion_ifs.hpp @@ -1,10 +1,10 @@ /** - * @file Quaternion_ifs.hpp + * @file quaternion_ifs.hpp * @brief Class for Quaternion (Inline functions) */ -#ifndef QUATERNION_IFS_HPP_ -#define QUATERNION_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_QUATERNION_IFS_H_ +#define S2E_LIBRARY_MATH_QUATERNION_IFS_H_ namespace libra { @@ -32,4 +32,4 @@ Quaternion::operator const Vector<4>&() const { return q_; } } // namespace libra -#endif // QUATERNION_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_QUATERNION_IFS_H_ diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index d1b17b022..5baa4d3e4 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ -#include +#include #include #include #include diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 25bd6b1bf..9457db80c 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ -#include +#include #include #include #include From e5f6db9854fa6969783bd2ed962d9f539427e536 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:32:24 +0100 Subject: [PATCH 0360/1086] Rename RandomWalk --- src/components/aocs/magnetorquer.hpp | 2 +- src/components/base_classes/sensor_base.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/library/math/{RandomWalk.hpp => random_walk.hpp} | 11 +++++++---- .../math/{RandomWalk_tfs.hpp => random_walk_tfs.hpp} | 8 +++++--- 7 files changed, 17 insertions(+), 12 deletions(-) rename src/library/math/{RandomWalk.hpp => random_walk.hpp} (83%) rename src/library/math/{RandomWalk_tfs.hpp => random_walk_tfs.hpp} (83%) diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index c8909adf3..2b85975d1 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index 7fa7bde29..2186595d8 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include /** diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index aa230d048..bfd602f76 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -10,7 +10,7 @@ using libra::NormalRand; #include #include "../library/math/global_randomization.hpp" -#include "../library/math/RandomWalk.hpp" +#include "../library/math/random_walk.hpp" #include "../interface/log_output/log_utility.hpp" using namespace std; diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 392b62ea8..023d9e9ca 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index d8f0a60f1..9d3d0908a 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include using libra::NormalRand; diff --git a/src/library/math/RandomWalk.hpp b/src/library/math/random_walk.hpp similarity index 83% rename from src/library/math/RandomWalk.hpp rename to src/library/math/random_walk.hpp index 8c1aaafe5..741e7eb76 100644 --- a/src/library/math/RandomWalk.hpp +++ b/src/library/math/random_walk.hpp @@ -1,13 +1,14 @@ /** - * @file RandomWalk.hpp + * @file random_walk.hpp * @brief Class to calculate random wark value */ -#pragma once +#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_H_ +#define S2E_LIBRARY_MATH_RANDOM_WALK_H_ +#include "./Vector.hpp" #include "./normal_randomization.hpp" #include "./ordinary_differential_equation.hpp" -#include "./Vector.hpp" /** * @class RandomWalk @@ -39,4 +40,6 @@ class RandomWalk : public libra::ODE { libra::NormalRand nrs_[N]; //!< Random walk excitation noise }; -#include "./RandomWalk_tfs.hpp" // template function definisions. +#include "./random_walk_tfs.hpp" // template function definisions. + +#endif // S2E_LIBRARY_MATH_RANDOM_WALK_H_ \ No newline at end of file diff --git a/src/library/math/RandomWalk_tfs.hpp b/src/library/math/random_walk_tfs.hpp similarity index 83% rename from src/library/math/RandomWalk_tfs.hpp rename to src/library/math/random_walk_tfs.hpp index 4682daf6e..523f09997 100644 --- a/src/library/math/RandomWalk_tfs.hpp +++ b/src/library/math/random_walk_tfs.hpp @@ -1,12 +1,12 @@ /** - * @file RandomWalk_tfs.hpp + * @file random_walk_tfs.hpp * @brief Class to calculate random wark value (template functions) */ -#pragma once +#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_TFS_H_ +#define S2E_LIBRARY_MATH_RANDOM_WALK_TFS_H_ #include - #include template @@ -31,3 +31,5 @@ void RandomWalk::RHS(double x, const libra::Vector& state, libra::Vector Date: Wed, 8 Feb 2023 16:33:23 +0100 Subject: [PATCH 0361/1086] Fix #define guard --- src/library/math/s2e_math.hpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/library/math/s2e_math.hpp b/src/library/math/s2e_math.hpp index 26a63b1cf..b5b3ebddb 100644 --- a/src/library/math/s2e_math.hpp +++ b/src/library/math/s2e_math.hpp @@ -3,7 +3,9 @@ * @brief Math functions */ -#pragma once +#ifndef S2E_LIBRARY_MATH_S2E_MATH_H_ +#define S2E_LIBRARY_MATH_S2E_MATH_H_ + #include namespace libra { @@ -16,3 +18,5 @@ namespace libra { double WrapTo2Pi(const double angle); } // namespace libra + +#endif // S2E_LIBRARY_MATH_S2E_MATH_H_ From 708b1e8265ebd9112538097d2cac6d4538ffc4ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:35:56 +0100 Subject: [PATCH 0362/1086] Rename TestQuaternion --- CMakeLists.txt | 2 +- src/library/math/{TestQuaternion.cpp => test_quaternion.cpp} | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) rename src/library/math/{TestQuaternion.cpp => test_quaternion.cpp} (96%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f6b9cb9e..fd54c6cbb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -211,7 +211,7 @@ if(GOOGLE_TEST) # Unit test set(TEST_PROJECT_NAME ${PROJECT_NAME}_TEST) set(TEST_FILES - src/library/math/Testquaternion.cpp + src/library/math/test_quaternion.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/src/library/math/TestQuaternion.cpp b/src/library/math/test_quaternion.cpp similarity index 96% rename from src/library/math/TestQuaternion.cpp rename to src/library/math/test_quaternion.cpp index 438280c49..915ff8f94 100644 --- a/src/library/math/TestQuaternion.cpp +++ b/src/library/math/test_quaternion.cpp @@ -1,5 +1,5 @@ /** - * @file Testquaternion.cpp + * @file test_quaternion.cpp * @brief Test codes for Quaternion class with GoogleTest */ #include From bfa5db0337631003437252a4489a2a1b411423a9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:41:56 +0100 Subject: [PATCH 0363/1086] Rename Vector --- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel.cpp | 2 +- src/components/aocs/reaction_wheel.hpp | 2 +- src/components/aocs/reaction_wheel_jitter.hpp | 2 +- src/components/aocs/reaction_wheel_ode.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- src/components/base_classes/sensor_base.hpp | 2 +- src/components/communication/antenna.hpp | 2 +- .../communication/ground_station_calculator.hpp | 2 +- src/components/communication/initialize_antenna.cpp | 2 +- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/mission/telescope.hpp | 2 +- src/components/power/csv_scenario_interface.hpp | 2 +- src/components/power/solar_array_panel.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/disturbance.hpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- .../solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/surface_force.cpp | 2 +- src/disturbances/surface_force.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/dynamics.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/interface/initialize/initialize_file_access.hpp | 2 +- src/library/geodesy/geodetic_position.hpp | 2 +- src/library/math/CMakeLists.txt | 2 +- src/library/math/matrix_vector.hpp | 2 +- src/library/math/ordinary_differential_equation.hpp | 2 +- src/library/math/quaternion.hpp | 2 +- src/library/math/random_walk.hpp | 2 +- src/library/math/{Vector.cpp => vector.cpp} | 4 ++-- src/library/math/{Vector.hpp => vector.hpp} | 12 ++++++------ src/library/math/{Vector_ifs.hpp => vector_ifs.hpp} | 9 +++++---- src/library/math/{Vector_tfs.hpp => vector_tfs.hpp} | 9 +++++---- src/library/optics/gaussian_beam_base.hpp | 2 +- src/library/orbit/kepler_orbit.hpp | 2 +- src/library/orbit/orbital_elements.hpp | 2 +- src/library/orbit/relative_orbit_models.hpp | 2 +- src/simulation/ground_station/ground_station.hpp | 2 +- .../initialize_monte_carlo_parameters.hpp | 2 +- .../monte_carlo_simulation_executor.hpp | 2 +- .../monte_carlo_simulation/simulation_object.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- .../sample_spacecraft/sample_components.hpp | 2 +- .../spacecraft/structure/initialize_structure.cpp | 2 +- .../spacecraft/structure/kinematics_parameters.hpp | 2 +- .../structure/residual_magnetic_moment.hpp | 2 +- src/simulation/spacecraft/structure/surface.hpp | 2 +- 62 files changed, 76 insertions(+), 74 deletions(-) rename src/library/math/{Vector.cpp => vector.cpp} (97%) rename src/library/math/{Vector.hpp => vector.hpp} (96%) rename src/library/math/{Vector_ifs.hpp => vector_ifs.hpp} (85%) rename src/library/math/{Vector_tfs.hpp => vector_tfs.hpp} (95%) diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 2b85975d1..6f506c5ab 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/components/aocs/reaction_wheel.cpp b/src/components/aocs/reaction_wheel.cpp index 1e7268748..a6e67fdff 100644 --- a/src/components/aocs/reaction_wheel.cpp +++ b/src/components/aocs/reaction_wheel.cpp @@ -5,7 +5,7 @@ #include "reaction_wheel.hpp" #include -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index 6dab0d807..3f46b5a57 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel_jitter.hpp b/src/components/aocs/reaction_wheel_jitter.hpp index 9eae459d3..098031a81 100644 --- a/src/components/aocs/reaction_wheel_jitter.hpp +++ b/src/components/aocs/reaction_wheel_jitter.hpp @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include /* diff --git a/src/components/aocs/reaction_wheel_ode.hpp b/src/components/aocs/reaction_wheel_ode.hpp index d03657f98..c1a15f9a0 100644 --- a/src/components/aocs/reaction_wheel_ode.hpp +++ b/src/components/aocs/reaction_wheel_ode.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ #include -#include +#include #include /* diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index e230c580d..8aaf901db 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 286b0b60c..76b2ef7b4 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index 2186595d8..3b22c516c 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include /** * @class SensorBase diff --git a/src/components/communication/antenna.hpp b/src/components/communication/antenna.hpp index a7eb89c95..af5d57ec2 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ #include -#include +#include using libra::Quaternion; using libra::Vector; #include diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index 475135f4d..5f27e44a5 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/communication/initialize_antenna.cpp b/src/components/communication/initialize_antenna.cpp index dad2bedce..6a7dd5575 100644 --- a/src/components/communication/initialize_antenna.cpp +++ b/src/components/communication/initialize_antenna.cpp @@ -8,7 +8,7 @@ #include -#include +#include #include "interface/initialize/initialize_file_access.hpp" diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index 96c4e3e90..3234e659a 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ #include -#include +#include #include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 75f81466c..5a87baecb 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ #include -#include +#include #include #include #include diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 9b9ffdf34..50c2fa047 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_MISSION_TELESCOPE_H_ #include -#include +#include #include #include #include diff --git a/src/components/power/csv_scenario_interface.hpp b/src/components/power/csv_scenario_interface.hpp index 116714a6a..7079073c0 100644 --- a/src/components/power/csv_scenario_interface.hpp +++ b/src/components/power/csv_scenario_interface.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ #define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ -#include +#include #include #include #include diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index 28de48605..d56de9e50 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ #define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ -#include +#include #include #include #include diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index cb49ac1d8..67593a6ea 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index ce3945de8..0b7cb0f01 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -10,7 +10,7 @@ #include #include "../library/math/quaternion.hpp" -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../environment/local/atmosphere.hpp" #include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 01ffe8596..a2a845428 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DISTURBANCES_DISTURBANCE_H_ #define S2E_DISTURBANCES_DISTURBANCE_H_ -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" using libra::Vector; /** diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 69e98ab42..63902e60c 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -10,7 +10,7 @@ #include "../library/math/matrix_vector.hpp" #include "../library/math/matrix.hpp" -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 19f12877a..a4c8d57fc 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -10,7 +10,7 @@ #include "../library/math/matrix_vector.hpp" #include "../library/math/matrix.hpp" -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index bc81bb609..49d29434c 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -8,7 +8,7 @@ #include -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" using libra::Vector; #include "../interface/log_output/loggable.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index bb13ca1d6..6bf158ab3 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,7 +9,7 @@ #include #include -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 5e6e5ea79..e07c731c0 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -5,7 +5,7 @@ #include "surface_force.hpp" -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 5c382684f..470a1ccdb 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -9,7 +9,7 @@ #define S2E_DISTURBANCES_SURFACE_FORCE_H_ #include "../library/math/quaternion.hpp" -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" #include "simple_disturbance.hpp" using libra::Quaternion; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 1d789490c..6e5026749 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index e647211f9..8e5b9fdae 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -7,7 +7,7 @@ #include -#include "../library/math/Vector.hpp" +#include "../library/math/vector.hpp" using libra::Vector; #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 5607a9855..2e1c1ebbb 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include using libra::Matrix; using libra::Quaternion; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 942359e1c..a3155a4ee 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -13,7 +13,7 @@ #include "library/math/matrix_vector.hpp" #include "library/math/matrix.hpp" #include "library/math/quaternion.hpp" -#include "library/math/Vector.hpp" +#include "library/math/vector.hpp" #include "celestial_rotation.hpp" #include "interface/log_output/loggable.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index d7da4e382..5fda5d5a9 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 46097be62..0eccffcb1 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 0f699d366..17e3a44a6 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -7,7 +7,7 @@ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ #include -#include +#include #include #include diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 023d9e9ca..71fc2326c 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include using libra::NormalRand; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 49c36a1d5..e61bca52f 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -10,7 +10,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index dcc397fda..1cf7116e4 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ #define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ -#include +#include using libra::Vector; #include using libra::Quaternion; diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index b42426194..3fc74708b 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -5,7 +5,7 @@ #include "solar_radiation_pressure_environment.hpp" #include -#include +#include #include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 295ab005c..5000a332c 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#include +#include #include #include diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index d781a8aff..963a6a34b 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -16,7 +16,7 @@ #include #endif #include -#include +#include #include #include #include diff --git a/src/library/geodesy/geodetic_position.hpp b/src/library/geodesy/geodetic_position.hpp index 1eeb897ae..f4161ef9f 100644 --- a/src/library/geodesy/geodetic_position.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -7,7 +7,7 @@ #define S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ #include -#include +#include /** * @class GeodeticPosition diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index 1675ffdf1..d7332a4d7 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -8,7 +8,7 @@ add_library(${PROJECT_NAME} STATIC quaternion.cpp Ran0.cpp Ran1.cpp - Vector.cpp + vector.cpp s2e_math.cpp ) diff --git a/src/library/math/matrix_vector.hpp b/src/library/math/matrix_vector.hpp index d082b7e2b..bd4d59b46 100644 --- a/src/library/math/matrix_vector.hpp +++ b/src/library/math/matrix_vector.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_H_ #define S2E_LIBRARY_MATH_MATRIX_VECTOR_H_P -#include "Vector.hpp" +#include "vector.hpp" #include "matrix.hpp" namespace libra { diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 8c979842b..57cc69b8b 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ #define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ -#include "./Vector.hpp" +#include "./vector.hpp" namespace libra { diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 635560716..c7e983648 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_QUATERNION_H_ #define S2E_LIBRARY_MATH_QUATERNION_H_ -#include "Vector.hpp" +#include "vector.hpp" #include "matrix.hpp" namespace libra { diff --git a/src/library/math/random_walk.hpp b/src/library/math/random_walk.hpp index 741e7eb76..54a3d5b92 100644 --- a/src/library/math/random_walk.hpp +++ b/src/library/math/random_walk.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_RANDOM_WALK_H_ #define S2E_LIBRARY_MATH_RANDOM_WALK_H_ -#include "./Vector.hpp" +#include "./vector.hpp" #include "./normal_randomization.hpp" #include "./ordinary_differential_equation.hpp" diff --git a/src/library/math/Vector.cpp b/src/library/math/vector.cpp similarity index 97% rename from src/library/math/Vector.cpp rename to src/library/math/vector.cpp index 3cade4ac1..446354053 100644 --- a/src/library/math/Vector.cpp +++ b/src/library/math/vector.cpp @@ -1,9 +1,9 @@ /** - * @file Vector.cpp + * @file vector.cpp * @brief Class for mathematical vector */ -#include "Vector.hpp" +#include "vector.hpp" #include "constants.hpp" diff --git a/src/library/math/Vector.hpp b/src/library/math/vector.hpp similarity index 96% rename from src/library/math/Vector.hpp rename to src/library/math/vector.hpp index db27bb75e..28889abdf 100644 --- a/src/library/math/Vector.hpp +++ b/src/library/math/vector.hpp @@ -1,10 +1,10 @@ /** - * @file Vector.hpp + * @file vector.hpp * @brief Class for mathematical vector */ -#ifndef VECTOR_HPP_ -#define VECTOR_HPP_ +#ifndef S2E_LIBRARY_MATH_VECTOR_H_ +#define S2E_LIBRARY_MATH_VECTOR_H_ #include // for size_t #include // for ostream, cout @@ -245,7 +245,7 @@ Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v); } // namespace libra -#include "Vector_ifs.hpp" // inline function definisions. -#include "Vector_tfs.hpp" // template function definisions. +#include "vector_ifs.hpp" // inline function definisions. +#include "vector_tfs.hpp" // template function definisions. -#endif // VECTOR_HPP_ +#endif // S2E_LIBRARY_MATH_VECTOR_H_ diff --git a/src/library/math/Vector_ifs.hpp b/src/library/math/vector_ifs.hpp similarity index 85% rename from src/library/math/Vector_ifs.hpp rename to src/library/math/vector_ifs.hpp index 7301a0a8a..54fe6fbe1 100644 --- a/src/library/math/Vector_ifs.hpp +++ b/src/library/math/vector_ifs.hpp @@ -1,9 +1,10 @@ /** - * @file Vector_ifs.hpp + * @file vector_ifs.hpp * @brief Class for mathematical vector (inline functions) */ -#ifndef VECTOR_IFS_HPP_ -#define VECTOR_IFS_HPP_ + +#ifndef S2E_LIBRARY_MATH_VECTOR_IFS_H_ +#define S2E_LIBRARY_MATH_VECTOR_IFS_H_ #include // for invalid_argument. @@ -45,4 +46,4 @@ T Vector::operator()(std::size_t pos) const { } // namespace libra -#endif // VECTOR_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_VECTOR_IFS_H_ diff --git a/src/library/math/Vector_tfs.hpp b/src/library/math/vector_tfs.hpp similarity index 95% rename from src/library/math/Vector_tfs.hpp rename to src/library/math/vector_tfs.hpp index a5a77e4c7..0f808b776 100644 --- a/src/library/math/Vector_tfs.hpp +++ b/src/library/math/vector_tfs.hpp @@ -1,9 +1,10 @@ /** - * @file Vector_tfs.hpp + * @file vector_tfs.hpp * @brief Class for mathematical vector (template functions) */ -#ifndef VECTOR_HPP_TFS_HPP_ -#define VECTOR_HPP_TFS_HPP_ + +#ifndef S2E_LIBRARY_MATH_VECTOR_TFS_H_ +#define S2E_LIBRARY_MATH_VECTOR_TFS_H_ #include @@ -145,4 +146,4 @@ double angle(const Vector& v1, const Vector& v2) { } // namespace libra -#endif // VECTOR_HPP_TFS_HPP_ +#endif // S2E_LIBRARY_MATH_VECTOR_TFS_H_ diff --git a/src/library/optics/gaussian_beam_base.hpp b/src/library/optics/gaussian_beam_base.hpp index 940fb1caf..2827a4cd1 100644 --- a/src/library/optics/gaussian_beam_base.hpp +++ b/src/library/optics/gaussian_beam_base.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ #define S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ -#include "../math/Vector.hpp" +#include "../math/vector.hpp" /** * @class GaussianBeamBase diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 0a8522a51..52c912678 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -7,7 +7,7 @@ #define S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ #include "../math/matrix.hpp" -#include "../math/Vector.hpp" +#include "../math/vector.hpp" #include "./orbital_elements.hpp" /** diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index 0f19fc657..92a4991f5 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ #define S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ -#include "../math/Vector.hpp" +#include "../math/vector.hpp" /** * @class OrbitalElements diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index 90acb2433..67fb2d376 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -7,7 +7,7 @@ #define S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ #include "../math/matrix.hpp" -#include "../math/Vector.hpp" +#include "../math/vector.hpp" /** * @enum RelativeOrbitModel diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 60857302c..ae0d0756f 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ #include -#include +#include #include #include diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 5baa4d3e4..ed118160d 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ #include -#include +#include #include #include #include diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 908034119..af69eff8d 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ -#include +#include #include #include // #include "simulation_object.hpp" diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 9457db80c..0550867ed 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ #include -#include +#include #include #include #include diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index d6aee2f0e..42e8cd524 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#include +#include #include /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 5ed01227b..03f6e2206 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#include +#include #include #include #include diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index d767578a3..40a06c558 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include #define MIN_VAL 1e-6 diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 04bcb0f85..c82f10d21 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ #include -#include +#include using libra::Matrix; using libra::Vector; diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 37ed4d09c..ff83b5c62 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ -#include +#include using libra::Vector; /** diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index ee4cd4735..169e33df5 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ -#include +#include using libra::Vector; /** From 9703e6be49d47433f1707c4d2c861c1525f15c44 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:44:58 +0100 Subject: [PATCH 0364/1086] Rename Ran0 and Ran1 --- src/components/aocs/star_sensor.hpp | 2 +- src/library/math/CMakeLists.txt | 4 ++-- src/library/math/global_randomization.hpp | 2 +- src/library/math/normal_randomization.hpp | 2 +- src/library/math/{Ran0.cpp => randomize0.cpp} | 4 ++-- src/library/math/{Ran0.hpp => randomize0.hpp} | 9 +++++---- src/library/math/{Ran1.cpp => randomize1.cpp} | 4 ++-- src/library/math/{Ran1.hpp => randomize1.hpp} | 10 +++++----- 8 files changed, 19 insertions(+), 18 deletions(-) rename src/library/math/{Ran0.cpp => randomize0.cpp} (92%) rename src/library/math/{Ran0.hpp => randomize0.hpp} (89%) rename src/library/math/{Ran1.cpp => randomize1.cpp} (94%) rename src/library/math/{Ran1.hpp => randomize1.hpp} (89%) diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 8aaf901db..9f37da946 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt index d7332a4d7..769797d4b 100644 --- a/src/library/math/CMakeLists.txt +++ b/src/library/math/CMakeLists.txt @@ -6,8 +6,8 @@ add_library(${PROJECT_NAME} STATIC normal_randomization.cpp quantization.cpp quaternion.cpp - Ran0.cpp - Ran1.cpp + randomize0.cpp + randomize1.cpp vector.cpp s2e_math.cpp ) diff --git a/src/library/math/global_randomization.hpp b/src/library/math/global_randomization.hpp index 55b7c7784..02f3733f5 100644 --- a/src/library/math/global_randomization.hpp +++ b/src/library/math/global_randomization.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ #define S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ -#include "./Ran0.hpp" +#include "./randomize0.hpp" /** * @class global_randomization.hpp diff --git a/src/library/math/normal_randomization.hpp b/src/library/math/normal_randomization.hpp index 6d39b1223..9fdfd9677 100644 --- a/src/library/math/normal_randomization.hpp +++ b/src/library/math/normal_randomization.hpp @@ -7,7 +7,7 @@ #ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ #define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ -#include "Ran1.hpp" +#include "randomize1.hpp" using libra::Ran1; namespace libra { diff --git a/src/library/math/Ran0.cpp b/src/library/math/randomize0.cpp similarity index 92% rename from src/library/math/Ran0.cpp rename to src/library/math/randomize0.cpp index d473221ec..df6d3bccb 100644 --- a/src/library/math/Ran0.cpp +++ b/src/library/math/randomize0.cpp @@ -1,10 +1,10 @@ /** - * @file Ran0.cpp + * @file randomize0.cpp * @brief Randomization with Park and Miller's multiplicative congruential method * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#include "Ran0.hpp" +#include "randomize0.hpp" using libra::Ran0; #include diff --git a/src/library/math/Ran0.hpp b/src/library/math/randomize0.hpp similarity index 89% rename from src/library/math/Ran0.hpp rename to src/library/math/randomize0.hpp index 1f567b7bb..61726fc2b 100644 --- a/src/library/math/Ran0.hpp +++ b/src/library/math/randomize0.hpp @@ -1,11 +1,11 @@ /** - * @file Ran0.hpp + * @file randomize0.hpp * @brief Randomization with Park and Miller's multiplicative congruential method * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#ifndef RAN0_HPP_ -#define RAN0_HPP_ +#ifndef S2E_LIBRARY_MATH_RANDOMIZE0_H_ +#define S2E_LIBRARY_MATH_RANDOMIZE0_H_ namespace libra { @@ -53,4 +53,5 @@ class Ran0 { }; } // namespace libra -#endif // RAN0_HPP_ + +#endif // S2E_LIBRARY_MATH_RANDOMIZE0_H_ diff --git a/src/library/math/Ran1.cpp b/src/library/math/randomize1.cpp similarity index 94% rename from src/library/math/Ran1.cpp rename to src/library/math/randomize1.cpp index c75b97725..118235b76 100644 --- a/src/library/math/Ran1.cpp +++ b/src/library/math/randomize1.cpp @@ -1,10 +1,10 @@ /** - * @file Ran1.cpp + * @file randomize1.cpp * @brief Randomization with Park and Miller's multiplicative congruential method combined with mixed method * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ -#include "Ran1.hpp" +#include "randomize1.hpp" using libra::Ran1; Ran1::Ran1() : y_(0) { init_(); } diff --git a/src/library/math/Ran1.hpp b/src/library/math/randomize1.hpp similarity index 89% rename from src/library/math/Ran1.hpp rename to src/library/math/randomize1.hpp index 67b24b114..696db295a 100644 --- a/src/library/math/Ran1.hpp +++ b/src/library/math/randomize1.hpp @@ -1,15 +1,15 @@ /** - * @file Ran1.hpp + * @file randomize1.hpp * @brief Randomization with Park and Miller's multiplicative congruential method combined with mixed method * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ -#ifndef RAN1_HPP_ -#define RAN1_HPP_ +#ifndef S2E_LIBRARY_MATH_RANDOMIZE1_H_ +#define S2E_LIBRARY_MATH_RANDOMIZE1_H_ #include // size_t -#include "Ran0.hpp" +#include "randomize0.hpp" namespace libra { @@ -61,4 +61,4 @@ class Ran1 { } // namespace libra -#endif // RAN1_HPP_ +#endif // S2E_LIBRARY_MATH_RANDOMIZE1_H_ From 9a82bd3e3888adfdf1ff69f4b0c6c2f9c60190c3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:47:54 +0100 Subject: [PATCH 0365/1086] Fix _H_ to _HPP_ --- src/components/aocs/gnss_receiver.hpp | 6 +++--- src/components/aocs/gyro_sensor.hpp | 8 ++++---- src/components/aocs/initialize_gnss_receiver.hpp | 6 +++--- src/components/aocs/initialize_gyro_sensor.hpp | 6 +++--- src/components/aocs/initialize_magnetometer.hpp | 6 +++--- src/components/aocs/initialize_magnetorquer.hpp | 6 +++--- src/components/aocs/initialize_reaction_wheel.hpp | 6 +++--- src/components/aocs/initialize_star_sensor.hpp | 6 +++--- src/components/aocs/initialize_sun_sensor.hpp | 6 +++--- src/components/aocs/magnetometer.hpp | 8 ++++---- src/components/aocs/magnetorquer.hpp | 10 +++++----- src/components/aocs/reaction_wheel.hpp | 8 ++++---- src/components/aocs/reaction_wheel_jitter.hpp | 6 +++--- src/components/aocs/reaction_wheel_ode.hpp | 6 +++--- src/components/aocs/star_sensor.hpp | 12 ++++++------ src/components/aocs/sun_sensor.hpp | 12 ++++++------ src/components/base_classes/component_base.hpp | 8 ++++---- .../i2c_controller_communication_base.hpp | 6 +++--- .../base_classes/initialize_sensor_base.hpp | 6 +++--- .../base_classes/initialize_sensor_base_tfs.hpp | 6 +++--- .../base_classes/interface_gpio_component.hpp | 6 +++--- src/components/base_classes/interface_tickable.hpp | 6 +++--- .../base_classes/obc_communication_base.hpp | 6 +++--- src/components/base_classes/obc_gpio_base.hpp | 6 +++--- .../obc_i2c_target_communication_base.hpp | 6 +++--- src/components/base_classes/sensor_base.hpp | 6 +++--- src/components/base_classes/sensor_base_tfs.hpp | 6 +++--- src/components/cdh/obc.hpp | 6 +++--- src/components/cdh/obc_c2a.hpp | 6 +++--- src/components/communication/antenna.hpp | 6 +++--- .../communication/antenna_radiation_pattern.hpp | 6 +++--- .../communication/ground_station_calculator.hpp | 12 ++++++------ src/components/communication/initialize_antenna.hpp | 6 +++--- .../initialize_ground_station_calculator.hpp | 6 +++--- src/components/examples/example_change_structure.hpp | 6 +++--- .../examples/example_i2c_controller_for_hils.hpp | 6 +++--- .../examples/example_i2c_target_for_hils.hpp | 6 +++--- .../example_serial_communication_for_hils.hpp | 6 +++--- .../example_serial_communication_with_obc.hpp | 6 +++--- src/components/ideal_components/force_generator.hpp | 10 +++++----- .../ideal_components/initialize_force_generator.hpp | 6 +++--- .../ideal_components/initialize_torque_generator.hpp | 6 +++--- src/components/ideal_components/torque_generator.hpp | 10 +++++----- src/components/mission/initialize_telescope.hpp | 6 +++--- src/components/mission/telescope.hpp | 6 +++--- src/components/power/battery.hpp | 6 +++--- src/components/power/csv_scenario_interface.hpp | 6 +++--- src/components/power/initialize_battery.hpp | 6 +++--- .../power/initialize_pcu_initial_study.hpp | 6 +++--- .../power/initialize_solar_array_panel.hpp | 6 +++--- src/components/power/pcu_initial_study.hpp | 6 +++--- src/components/power/power_control_unit.hpp | 6 +++--- src/components/power/solar_array_panel.hpp | 6 +++--- .../propulsion/initialize_simple_thruster.hpp | 6 +++--- src/components/propulsion/simple_thruster.hpp | 6 +++--- src/disturbances/acceleration_disturbance.hpp | 6 +++--- src/disturbances/air_drag.hpp | 6 +++--- src/disturbances/disturbance.hpp | 6 +++--- src/disturbances/disturbances.hpp | 6 +++--- src/disturbances/geopotential.hpp | 6 +++--- src/disturbances/gravity_gradient.hpp | 6 +++--- src/disturbances/initialize_disturbances.hpp | 6 +++--- src/disturbances/magnetic_disturbance.hpp | 6 +++--- src/disturbances/simple_disturbance.hpp | 6 +++--- .../solar_radiation_pressure_disturbance.hpp | 6 +++--- src/disturbances/surface_force.hpp | 6 +++--- src/disturbances/third_body_gravity.hpp | 6 +++--- src/dynamics/attitude/attitude.hpp | 6 +++--- src/dynamics/attitude/attitude_rk4.hpp | 6 +++--- src/dynamics/attitude/controlled_attitude.hpp | 6 +++--- src/dynamics/attitude/initialize_attitude.hpp | 6 +++--- src/dynamics/dynamics.hpp | 6 +++--- src/dynamics/orbit/encke_orbit_propagation.hpp | 6 +++--- src/dynamics/orbit/initialize_orbit.hpp | 6 +++--- src/dynamics/orbit/kepler_orbit_propagation.hpp | 6 +++--- src/dynamics/orbit/orbit.hpp | 6 +++--- src/dynamics/orbit/relative_orbit.hpp | 6 +++--- src/dynamics/orbit/rk4_orbit_propagation.hpp | 6 +++--- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 6 +++--- src/dynamics/thermal/initialize_node.hpp | 6 +++--- src/dynamics/thermal/initialize_temperature.hpp | 6 +++--- src/dynamics/thermal/node.hpp | 6 +++--- src/dynamics/thermal/temperature.hpp | 6 +++--- src/environment/global/celestial_information.hpp | 6 +++--- src/environment/global/celestial_rotation.hpp | 6 +++--- src/environment/global/clock_generator.hpp | 6 +++--- src/environment/global/global_environment.hpp | 6 +++--- src/environment/global/gnss_satellites.hpp | 6 +++--- src/environment/global/hipparcos_catalogue.hpp | 6 +++--- .../global/initialize_global_environment.hpp | 6 +++--- .../global/initialize_gnss_satellites.hpp | 6 +++--- src/environment/global/physical_constants.hpp | 6 +++--- src/environment/global/simulation_time.hpp | 6 +++--- src/environment/local/atmosphere.hpp | 6 +++--- src/environment/local/geomagnetic_field.hpp | 6 +++--- .../local/initialize_local_environment.hpp | 6 +++--- .../local/local_celestial_information.hpp | 6 +++--- src/environment/local/local_environment.hpp | 6 +++--- .../local/solar_radiation_pressure_environment.hpp | 6 +++--- src/interface/hils/com_port_interface.hpp | 6 +++--- src/interface/hils/hils_port_manager.hpp | 6 +++--- src/interface/hils/ports/hils_i2c_target_port.hpp | 6 +++--- src/interface/hils/ports/hils_uart_port.hpp | 6 +++--- src/interface/initialize/initialize_file_access.hpp | 6 +++--- src/interface/log_output/initialize_log.hpp | 6 +++--- src/interface/log_output/log_utility.hpp | 6 +++--- src/interface/log_output/loggable.hpp | 6 +++--- src/interface/log_output/logger.hpp | 6 +++--- src/interface/sils/ports/gpio_port.hpp | 6 +++--- src/interface/sils/ports/i2c_port.hpp | 6 +++--- src/interface/sils/ports/power_port.hpp | 6 +++--- src/interface/sils/ports/uart_port.hpp | 6 +++--- src/interface/sils/utility/ring_buffer.hpp | 6 +++--- src/library/geodesy/geodetic_position.hpp | 6 +++--- src/library/math/constants.hpp | 6 +++--- src/library/math/global_randomization.hpp | 6 +++--- src/library/math/matrix.hpp | 6 +++--- src/library/math/matrix_ifs.hpp | 6 +++--- src/library/math/matrix_tfs.hpp | 6 +++--- src/library/math/matrix_vector.hpp | 6 +++--- src/library/math/matrix_vector_impl.hpp | 6 +++--- src/library/math/normal_randomization.hpp | 6 +++--- src/library/math/normal_randomization_ifs.hpp | 6 +++--- src/library/math/ordinary_differential_equation.hpp | 6 +++--- .../math/ordinary_differential_equation_ifs.hpp | 6 +++--- .../math/ordinary_differential_equation_impl.hpp | 6 +++--- .../math/ordinary_differential_equation_tfs.hpp | 6 +++--- src/library/math/quantization.hpp | 6 +++--- src/library/math/quaternion.hpp | 6 +++--- src/library/math/quaternion_ifs.hpp | 6 +++--- src/library/math/random_walk.hpp | 6 +++--- src/library/math/random_walk_tfs.hpp | 6 +++--- src/library/math/randomize0.hpp | 6 +++--- src/library/math/randomize1.hpp | 6 +++--- src/library/math/s2e_math.hpp | 6 +++--- src/library/math/vector.hpp | 6 +++--- src/library/math/vector_ifs.hpp | 6 +++--- src/library/math/vector_tfs.hpp | 6 +++--- src/library/nrlmsise00/wrapper_nrlmsise00.hpp | 6 +++--- src/library/optics/gaussian_beam_base.hpp | 6 +++--- src/library/orbit/kepler_orbit.hpp | 6 +++--- src/library/orbit/orbital_elements.hpp | 6 +++--- src/library/orbit/relative_orbit_models.hpp | 6 +++--- src/library/utilities/endian.h | 6 +++--- src/library/utilities/endian_define.hpp | 6 +++--- src/library/utilities/macros.hpp | 6 +++--- src/library/utilities/slip.h | 6 +++--- src/relative_information/relative_information.hpp | 6 +++--- src/simulation/case/sample_case.hpp | 6 +++--- src/simulation/case/simulation_case.hpp | 6 +++--- src/simulation/ground_station/ground_station.hpp | 6 +++--- .../sample_ground_station/sample_ground_station.hpp | 6 +++--- .../sample_ground_station_components.hpp | 6 +++--- .../inter_spacecraft_communication.hpp | 6 +++--- .../initialize_monte_carlo_parameters.hpp | 6 +++--- .../initialize_monte_carlo_simulation.hpp | 6 +++--- .../monte_carlo_simulation_executor.hpp | 6 +++--- .../monte_carlo_simulation/simulation_object.hpp | 6 +++--- src/simulation/simulation_configuration.hpp | 6 +++--- src/simulation/spacecraft/installed_components.hpp | 6 +++--- .../sample_spacecraft/sample_components.hpp | 6 +++--- .../sample_spacecraft/sample_port_configuration.hpp | 6 +++--- .../sample_spacecraft/sample_spacecraft.hpp | 6 +++--- src/simulation/spacecraft/spacecraft.hpp | 6 +++--- .../spacecraft/structure/initialize_structure.hpp | 6 +++--- .../spacecraft/structure/kinematics_parameters.hpp | 6 +++--- .../structure/residual_magnetic_moment.hpp | 6 +++--- src/simulation/spacecraft/structure/structure.hpp | 6 +++--- src/simulation/spacecraft/structure/surface.hpp | 6 +++--- 169 files changed, 526 insertions(+), 526 deletions(-) diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 91eb95dad..78ee19bdc 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate GNSS receiver */ -#ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ -#define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ +#ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ +#define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ #include #include @@ -214,4 +214,4 @@ class GNSSReceiver : public ComponentBase, public ILoggable { void ConvertJulianDayToGPSTime(const double JulianDay); }; -#endif // S2E_COMPONENTS_AOCS_GNSS_RECEIVER_H_ +#endif // S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index a51966f70..e24dbf7a2 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -3,12 +3,12 @@ * @brief Class to emulate gyro sensor (angular velocity sensor) */ -#ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ -#include #include #include +#include #include "../base_classes/component_base.hpp" #include "../base_classes/sensor_base.hpp" @@ -85,4 +85,4 @@ class Gyro : public ComponentBase, public SensorBase, public ILoggable const Dynamics* dynamics_; //!< Dynamics information }; -#endif // S2E_COMPONENTS_AOCS_GYRO_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_gnss_receiver.hpp b/src/components/aocs/initialize_gnss_receiver.hpp index a18b9ac57..908b044dd 100644 --- a/src/components/aocs/initialize_gnss_receiver.hpp +++ b/src/components/aocs/initialize_gnss_receiver.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for GNSS Receiver */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ #include @@ -34,4 +34,4 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/aocs/initialize_gyro_sensor.hpp b/src/components/aocs/initialize_gyro_sensor.hpp index 3aac32a8b..bec1b016f 100644 --- a/src/components/aocs/initialize_gyro_sensor.hpp +++ b/src/components/aocs/initialize_gyro_sensor.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for gyro sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ #include @@ -31,4 +31,4 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_magnetometer.hpp b/src/components/aocs/initialize_magnetometer.hpp index 196fb12ea..196e3547b 100644 --- a/src/components/aocs/initialize_magnetometer.hpp +++ b/src/components/aocs/initialize_magnetometer.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for magnetometer */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ #include @@ -31,4 +31,4 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/aocs/initialize_magnetorquer.hpp b/src/components/aocs/initialize_magnetorquer.hpp index ff232912f..e3e7e3111 100644 --- a/src/components/aocs/initialize_magnetorquer.hpp +++ b/src/components/aocs/initialize_magnetorquer.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for magnetorquer */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ #include @@ -31,4 +31,4 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/aocs/initialize_reaction_wheel.hpp b/src/components/aocs/initialize_reaction_wheel.hpp index 4e5315e14..5cd94d3a6 100644 --- a/src/components/aocs/initialize_reaction_wheel.hpp +++ b/src/components/aocs/initialize_reaction_wheel.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for Reaction Wheel */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ #include @@ -31,4 +31,4 @@ RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, double compo_update_step); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ diff --git a/src/components/aocs/initialize_star_sensor.hpp b/src/components/aocs/initialize_star_sensor.hpp index 20aceb1ec..59325efc4 100644 --- a/src/components/aocs/initialize_star_sensor.hpp +++ b/src/components/aocs/initialize_star_sensor.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for star sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ #include @@ -34,4 +34,4 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const std::string fname, d STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_sun_sensor.hpp b/src/components/aocs/initialize_sun_sensor.hpp index 24fb6c8f6..4eba4b5f1 100644 --- a/src/components/aocs/initialize_sun_sensor.hpp +++ b/src/components/aocs/initialize_sun_sensor.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for sun sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ #include @@ -32,4 +32,4 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::str SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 9aef3ca26..5e62223b0 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -3,12 +3,12 @@ * @brief Class to emulate magnetometer */ -#ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ -#define S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ +#ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ +#define S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ -#include #include #include +#include #include "../base_classes/component_base.hpp" #include "../base_classes/sensor_base.hpp" @@ -85,4 +85,4 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg const MagEnvironment* magnet_; //!< Geomagnetic environment }; -#endif // S2E_COMPONENTS_AOCS_MAGNETOMETER_H_ +#endif // S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 6f506c5ab..2fcb2a31a 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -3,16 +3,16 @@ * @brief Class to emulate magnetorquer */ -#ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ -#define S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ +#ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ +#define S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ +#include +#include #include #include #include #include #include -#include -#include #include "../base_classes/component_base.hpp" @@ -134,4 +134,4 @@ class MagTorquer : public ComponentBase, public ILoggable { libra::Vector CalcOutputTorque(void); }; -#endif // S2E_COMPONENTS_AOCS_MAGNETORQUER_H_ +#endif // S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index 3f46b5a57..847405548 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -3,12 +3,12 @@ * @brief Class to emulate Reaction Wheel */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ -#include #include #include +#include #include #include #include @@ -235,4 +235,4 @@ class RWModel : public ComponentBase, public ILoggable { void Initialize(); }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_H_ +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ diff --git a/src/components/aocs/reaction_wheel_jitter.hpp b/src/components/aocs/reaction_wheel_jitter.hpp index 098031a81..c904f6d0a 100644 --- a/src/components/aocs/reaction_wheel_jitter.hpp +++ b/src/components/aocs/reaction_wheel_jitter.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate RW high-frequency jitter effect */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ #pragma once #include @@ -122,4 +122,4 @@ class RWJitter { void CalcCoef(); }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_H_ +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ diff --git a/src/components/aocs/reaction_wheel_ode.hpp b/src/components/aocs/reaction_wheel_ode.hpp index c1a15f9a0..db4c74e1d 100644 --- a/src/components/aocs/reaction_wheel_ode.hpp +++ b/src/components/aocs/reaction_wheel_ode.hpp @@ -3,8 +3,8 @@ * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ +#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ +#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ #include #include @@ -70,4 +70,4 @@ class RwOde : public libra::ODE<1> { double target_angular_velocity_; //!< Target angular velocity [rad/s] }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_H_ +#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 9f37da946..ba883516e 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -3,16 +3,16 @@ * @brief Class to emulate star tracker */ -#ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ +#include +#include +#include #include #include #include #include -#include -#include -#include #include #include "../base_classes/component_base.hpp" @@ -203,4 +203,4 @@ class STT : public ComponentBase, public ILoggable { void Initialize(); }; -#endif // S2E_COMPONENTS_AOCS_STAR_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 76b2ef7b4..7714fabf8 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -3,15 +3,15 @@ * @brief Class to emulate sun sensor */ -#ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ -#define S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ +#ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ +#define S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ -#include -#include -#include #include #include #include +#include +#include +#include #include "../base_classes/component_base.hpp" @@ -139,4 +139,4 @@ class SunSensor : public ComponentBase, public ILoggable { void CalcSolarIlluminance(); }; -#endif // S2E_COMPONENTS_AOCS_SUN_SENSOR_H_ +#endif // S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ diff --git a/src/components/base_classes/component_base.hpp b/src/components/base_classes/component_base.hpp index 26ed8571d..bee09392a 100644 --- a/src/components/base_classes/component_base.hpp +++ b/src/components/base_classes/component_base.hpp @@ -3,12 +3,12 @@ * @brief Base class for component emulation. All components have to inherit this. */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ -#include #include #include +#include #include "interface_tickable.hpp" @@ -88,4 +88,4 @@ class ComponentBase : public ITickable { PowerPort* power_port_; //!< Power port }; -#endif // S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ diff --git a/src/components/base_classes/i2c_controller_communication_base.hpp b/src/components/base_classes/i2c_controller_communication_base.hpp index 4942b3138..fc09af8a2 100644 --- a/src/components/base_classes/i2c_controller_communication_base.hpp +++ b/src/components/base_classes/i2c_controller_communication_base.hpp @@ -3,8 +3,8 @@ * @brief This class simulates the I2C Controller communication with the I2C Target. */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ #include "../../interface/hils/hils_port_manager.hpp" #include "obc_communication_base.hpp" @@ -64,4 +64,4 @@ class I2cControllerCommunicationBase { HilsPortManager* hils_port_manager_; //!< HILS port manager }; -#endif // S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ diff --git a/src/components/base_classes/initialize_sensor_base.hpp b/src/components/base_classes/initialize_sensor_base.hpp index 1748dfeb8..b8fbec8e5 100644 --- a/src/components/base_classes/initialize_sensor_base.hpp +++ b/src/components/base_classes/initialize_sensor_base.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for SensorBase class */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ #include "sensor_base.hpp" @@ -23,4 +23,4 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl #include "initialize_sensor_base_tfs.hpp" -#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ diff --git a/src/components/base_classes/initialize_sensor_base_tfs.hpp b/src/components/base_classes/initialize_sensor_base_tfs.hpp index f5722e3a0..1815c850a 100644 --- a/src/components/base_classes/initialize_sensor_base_tfs.hpp +++ b/src/components/base_classes/initialize_sensor_base_tfs.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for SensorBase class (template functions) */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ -#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ #include "interface/initialize/initialize_file_access.hpp" @@ -51,4 +51,4 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl return sensor_base; } -#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ diff --git a/src/components/base_classes/interface_gpio_component.hpp b/src/components/base_classes/interface_gpio_component.hpp index de6691c7c..9f2885792 100644 --- a/src/components/base_classes/interface_gpio_component.hpp +++ b/src/components/base_classes/interface_gpio_component.hpp @@ -3,8 +3,8 @@ * @brief Interface class for components which have GPIO port */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ -#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_HPP_ /** * @class IGPIOCompo @@ -27,4 +27,4 @@ class IGPIOCompo { virtual void GPIOStateChanged(int port_id, bool isPosedge) = 0; }; -#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_HPP_ diff --git a/src/components/base_classes/interface_tickable.hpp b/src/components/base_classes/interface_tickable.hpp index 4779220b9..dd185fab6 100644 --- a/src/components/base_classes/interface_tickable.hpp +++ b/src/components/base_classes/interface_tickable.hpp @@ -3,8 +3,8 @@ * @brief Interface class for time update of components */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_HPP_ /** * @class ITickable @@ -40,4 +40,4 @@ class ITickable { bool needs_fast_update_ = false; //!< Whether or not high-frequency disturbances need to be calculated }; -#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_TICKABLE_HPP_ diff --git a/src/components/base_classes/obc_communication_base.hpp b/src/components/base_classes/obc_communication_base.hpp index 3425910a2..5282f795c 100644 --- a/src/components/base_classes/obc_communication_base.hpp +++ b/src/components/base_classes/obc_communication_base.hpp @@ -3,8 +3,8 @@ * @brief Base class for serial communication (e.g., UART) with OBC flight software */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ #include @@ -128,4 +128,4 @@ class ObcCommunicationBase { virtual int GenerateTelemetry() = 0; }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ diff --git a/src/components/base_classes/obc_gpio_base.hpp b/src/components/base_classes/obc_gpio_base.hpp index bd1d84d48..282efa638 100644 --- a/src/components/base_classes/obc_gpio_base.hpp +++ b/src/components/base_classes/obc_gpio_base.hpp @@ -4,8 +4,8 @@ * TODO: consider relation with IGPIOCompo */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ #include "../cdh/obc.hpp" @@ -50,4 +50,4 @@ class ObcGpioBase { OBC* obc_; //!< The communication target OBC }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ diff --git a/src/components/base_classes/obc_i2c_target_communication_base.hpp b/src/components/base_classes/obc_i2c_target_communication_base.hpp index 81b6810c5..f3ffe5b9c 100644 --- a/src/components/base_classes/obc_i2c_target_communication_base.hpp +++ b/src/components/base_classes/obc_i2c_target_communication_base.hpp @@ -3,8 +3,8 @@ * @brief Base class for I2C communication as target side with OBC flight software */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ #include "../../interface/hils/hils_port_manager.hpp" #include "../cdh/obc.hpp" @@ -121,4 +121,4 @@ class ObcI2cTargetCommunicationBase { HilsPortManager* hils_port_manager_; //!< HILS port manager }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_H_ +#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base_classes/sensor_base.hpp index 3b22c516c..2559db33f 100644 --- a/src/components/base_classes/sensor_base.hpp +++ b/src/components/base_classes/sensor_base.hpp @@ -3,8 +3,8 @@ * @brief Base class for sensor emulation to add noises */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ -#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ #include #include @@ -73,4 +73,4 @@ class SensorBase { #include "./sensor_base_tfs.hpp" // template function definisions. -#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_H_ \ No newline at end of file +#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ \ No newline at end of file diff --git a/src/components/base_classes/sensor_base_tfs.hpp b/src/components/base_classes/sensor_base_tfs.hpp index 2f0e03c4f..34415e208 100644 --- a/src/components/base_classes/sensor_base_tfs.hpp +++ b/src/components/base_classes/sensor_base_tfs.hpp @@ -3,8 +3,8 @@ * @brief Base class for sensor emulation to add noises */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ -#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ +#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ +#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ #include @@ -73,4 +73,4 @@ void SensorBase::RangeCheck(void) { } } -#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_H_ \ No newline at end of file +#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ \ No newline at end of file diff --git a/src/components/cdh/obc.hpp b/src/components/cdh/obc.hpp index fffc55518..99237238f 100644 --- a/src/components/cdh/obc.hpp +++ b/src/components/cdh/obc.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate on board computer */ -#ifndef S2E_COMPONENTS_CDH_OBC_H_ -#define S2E_COMPONENTS_CDH_OBC_H_ +#ifndef S2E_COMPONENTS_CDH_OBC_HPP_ +#define S2E_COMPONENTS_CDH_OBC_HPP_ #include #include @@ -206,4 +206,4 @@ class OBC : public ComponentBase { std::map gpio_ports_; //!< GPIO ports }; -#endif // S2E_COMPONENTS_CDH_OBC_H_ +#endif // S2E_COMPONENTS_CDH_OBC_HPP_ diff --git a/src/components/cdh/obc_c2a.hpp b/src/components/cdh/obc_c2a.hpp index 9fad1d1fa..84c6134f5 100644 --- a/src/components/cdh/obc_c2a.hpp +++ b/src/components/cdh/obc_c2a.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate on board computer with C2A flight software */ -#ifndef S2E_COMPONENTS_CDH_OBC_C2A_H_ -#define S2E_COMPONENTS_CDH_OBC_C2A_H_ +#ifndef S2E_COMPONENTS_CDH_OBC_C2A_HPP_ +#define S2E_COMPONENTS_CDH_OBC_C2A_HPP_ #include @@ -287,4 +287,4 @@ int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned int OBC_C2A_GpioWrite(int port_id, const bool is_high); bool OBC_C2A_GpioRead(int port_id); // return false when the port_id is not used -#endif // S2E_COMPONENTS_CDH_OBC_C2A_H_ +#endif // S2E_COMPONENTS_CDH_OBC_C2A_HPP_ diff --git a/src/components/communication/antenna.hpp b/src/components/communication/antenna.hpp index af5d57ec2..7cd039fa9 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/communication/antenna.hpp @@ -3,8 +3,8 @@ * @brief Component emulation: RF antenna */ -#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ -#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ +#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ +#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ #include #include @@ -150,4 +150,4 @@ class Antenna { AntennaGainModel SetAntennaGainModel(const std::string gain_model_name); -#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_H_ +#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ diff --git a/src/components/communication/antenna_radiation_pattern.hpp b/src/components/communication/antenna_radiation_pattern.hpp index 1e23f4e63..02149054a 100644 --- a/src/components/communication/antenna_radiation_pattern.hpp +++ b/src/components/communication/antenna_radiation_pattern.hpp @@ -3,8 +3,8 @@ * @brief Class to manage antenna radiation pattern */ -#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ -#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ +#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ +#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ #include #include @@ -62,4 +62,4 @@ class AntennaRadiationPattern { std::vector> gain_dBi_; //!< Antenna gain table [dBi] }; -#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_H_ +#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index 5f27e44a5..92f14ea01 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -4,16 +4,16 @@ * @note TODO: This class is not `Component`. We need to move this to `Analysis` category and use this as library in future. */ -#ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ -#define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ +#ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ +#define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ -#include -#include -#include #include #include #include #include +#include +#include +#include #include using libra::Matrix; @@ -138,4 +138,4 @@ class GScalculator : public ILoggable { double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); }; -#endif // S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_H_ +#endif // S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/communication/initialize_antenna.hpp b/src/components/communication/initialize_antenna.hpp index 94aaaaea6..c21a7bb1d 100644 --- a/src/components/communication/initialize_antenna.hpp +++ b/src/components/communication/initialize_antenna.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for Antenna */ -#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ -#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ +#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ +#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ #include @@ -16,4 +16,4 @@ */ Antenna InitAntenna(const int antenna_id, const std::string file_name); -#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_H_ +#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ diff --git a/src/components/communication/initialize_ground_station_calculator.hpp b/src/components/communication/initialize_ground_station_calculator.hpp index 39fa2337a..7c17b689a 100644 --- a/src/components/communication/initialize_ground_station_calculator.hpp +++ b/src/components/communication/initialize_ground_station_calculator.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for Ground Station Calculator */ -#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ -#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ +#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ +#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ #include @@ -16,4 +16,4 @@ GScalculator InitGScalculator(const std::string fname); -#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_H_ +#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 1187683a5..15fcc3329 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -3,8 +3,8 @@ * @brief Class to show an example to change satellite structure information */ -#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ -#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_HPP_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_HPP_ #include #include @@ -53,4 +53,4 @@ class ExampleChangeStructure : public ComponentBase, public ILoggable { Structure* structure_; //!< Structure information }; -#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_H_ +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_HPP_ diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index b8d92f66a..5319be4dd 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -3,8 +3,8 @@ * @brief Example of component emulation for I2C controller side communication in HILS environment */ -#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ -#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_HPP_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_HPP_ #include @@ -65,4 +65,4 @@ class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCo static const uint8_t kCmdFooter_ = 0x50; //!< 'P' Footer for SC18IM700 }; -#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_H_ +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_CONTROLLER_FOR_HILS_HPP_ diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 8f72b0077..f2b3029ce 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -3,8 +3,8 @@ * @brief Example of component emulation for I2C target side communication in HILS environment */ -#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ -#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_HPP_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_HPP_ #include @@ -54,4 +54,4 @@ class ExampleI2cTargetForHils : public ComponentBase, public ObcI2cTargetCommuni const unsigned char kNumAlphabet = 26; //!< Number of alphabet }; -#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_H_ +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_I2C_TARGET_FOR_HILS_HPP_ diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 29b6c16d3..58be3e357 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -3,8 +3,8 @@ * @brief Example of component emulation for UART communication in HILS environment */ -#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ -#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_HPP_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_HPP_ #include @@ -71,4 +71,4 @@ class ExampleSerialCommunicationForHils : public ComponentBase, public ObcCommun int GenerateTelemetry() override; }; -#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_H_ +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_FOR_HILS_HPP_ diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 9102426e0..3b4835ece 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -3,8 +3,8 @@ * @brief Example of component emulation with communication between OBC Flight software */ -#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ -#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ +#ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_HPP_P_ +#define S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_HPP_P_ #include @@ -92,4 +92,4 @@ class ExampleSerialCommunicationWithObc : public ComponentBase, public ObcCommun int Initialize(); }; -#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_H_ +#endif // S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_HPP_P_ diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index 3234e659a..c801ab3c2 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -3,14 +3,14 @@ * @brief Ideal component which can generate force for control algorithm test */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ -#include -#include #include #include #include +#include +#include /* * @class ForceGenerator @@ -115,4 +115,4 @@ class ForceGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_H_ +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/initialize_force_generator.hpp b/src/components/ideal_components/initialize_force_generator.hpp index 639aa15f6..71b22e5eb 100644 --- a/src/components/ideal_components/initialize_force_generator.hpp +++ b/src/components/ideal_components/initialize_force_generator.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for ForceGenerator */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ #include "force_generator.hpp" @@ -17,4 +17,4 @@ */ ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_H_ +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/initialize_torque_generator.hpp b/src/components/ideal_components/initialize_torque_generator.hpp index 5ce2bd365..9272856f8 100644 --- a/src/components/ideal_components/initialize_torque_generator.hpp +++ b/src/components/ideal_components/initialize_torque_generator.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for TorqueGenerator */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ #include "torque_generator.hpp" @@ -17,4 +17,4 @@ */ TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_H_ +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 5a87baecb..26db28950 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -3,14 +3,14 @@ * @brief Ideal component which can generate torque for control algorithm test */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ +#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ -#include -#include #include #include #include +#include +#include /* * @class TorqueGenerator @@ -93,4 +93,4 @@ class TorqueGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_H_ +#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ diff --git a/src/components/mission/initialize_telescope.hpp b/src/components/mission/initialize_telescope.hpp index fa1584efc..de01db35d 100644 --- a/src/components/mission/initialize_telescope.hpp +++ b/src/components/mission/initialize_telescope.hpp @@ -3,8 +3,8 @@ * @brief Initialize function of Telescope */ -#ifndef S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ -#define S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ +#ifndef S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ +#define S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ #include @@ -21,4 +21,4 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); -#endif // S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_H_ +#endif // S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 50c2fa047..940ff10a6 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -3,8 +3,8 @@ * @brief Component emulation: Telescope */ -#ifndef S2E_COMPONENTS_MISSION_TELESCOPE_H_ -#define S2E_COMPONENTS_MISSION_TELESCOPE_H_ +#ifndef S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ +#define S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ #include #include @@ -123,4 +123,4 @@ class Telescope : public ComponentBase, public ILoggable { //************************************************************* }; -#endif // S2E_COMPONENTS_MISSION_TELESCOPE_H_ +#endif // S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ diff --git a/src/components/power/battery.hpp b/src/components/power/battery.hpp index 9e60828d6..1d0fa649d 100644 --- a/src/components/power/battery.hpp +++ b/src/components/power/battery.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of battery */ -#ifndef S2E_COMPONENTS_POWER_BATTERY_H_ -#define S2E_COMPONENTS_POWER_BATTERY_H_ +#ifndef S2E_COMPONENTS_POWER_BATTERY_HPP_P_ +#define S2E_COMPONENTS_POWER_BATTERY_HPP_P_ #include #include @@ -132,4 +132,4 @@ class BAT : public ComponentBase, public ILoggable { void UpdateBatVoltage(); }; -#endif // S2E_COMPONENTS_POWER_BATTERY_H_ +#endif // S2E_COMPONENTS_POWER_BATTERY_HPP_P_ diff --git a/src/components/power/csv_scenario_interface.hpp b/src/components/power/csv_scenario_interface.hpp index 7079073c0..73b30008c 100644 --- a/src/components/power/csv_scenario_interface.hpp +++ b/src/components/power/csv_scenario_interface.hpp @@ -3,8 +3,8 @@ * @brief Interface to read power related scenario in CSV file */ -#ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ -#define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ +#ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ +#define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ #include #include @@ -78,4 +78,4 @@ class CsvScenarioInterface { static std::map buffers_; //!< Buffer }; -#endif // S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_H_ +#endif // S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ diff --git a/src/components/power/initialize_battery.hpp b/src/components/power/initialize_battery.hpp index 8ef11bff1..2e80452d4 100644 --- a/src/components/power/initialize_battery.hpp +++ b/src/components/power/initialize_battery.hpp @@ -3,8 +3,8 @@ * @brief Initialize function of BAT */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ -#define S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ +#define S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ #include @@ -18,4 +18,4 @@ */ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_H_ +#endif // S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/power/initialize_pcu_initial_study.hpp b/src/components/power/initialize_pcu_initial_study.hpp index 7d99e6d94..631e2ece4 100644 --- a/src/components/power/initialize_pcu_initial_study.hpp +++ b/src/components/power/initialize_pcu_initial_study.hpp @@ -3,8 +3,8 @@ * @brief Initialize function of PCU_InitialStudy */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ -#define S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ +#define S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ #include @@ -21,4 +21,4 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_H_ +#endif // S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/power/initialize_solar_array_panel.hpp b/src/components/power/initialize_solar_array_panel.hpp index 18cd702f7..2a9280059 100644 --- a/src/components/power/initialize_solar_array_panel.hpp +++ b/src/components/power/initialize_solar_array_panel.hpp @@ -3,8 +3,8 @@ * @brief Initialize function of SAP (Solar Array Panel) */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ -#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ +#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ +#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ #include @@ -32,4 +32,4 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons */ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_H_ +#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index b971d0382..d21597279 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of Power Control Unit for initial study of spacecraft project */ -#ifndef S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ -#define S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ +#ifndef S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ +#define S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ #include #include @@ -81,4 +81,4 @@ class PCU_InitialStudy : public ComponentBase, public ILoggable { void UpdateChargeCurrentAndBusVoltage(); }; -#endif // S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_H_ +#endif // S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/power/power_control_unit.hpp b/src/components/power/power_control_unit.hpp index a9d7aefae..bf6ce95fd 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/power/power_control_unit.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of Power Control Unit */ -#ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ -#define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ +#ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ +#define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ #include #include @@ -94,4 +94,4 @@ class PCU : public ComponentBase, public ILoggable { std::map ports_; //!< Power port list }; -#endif // S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_H_ +#endif // S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index d56de9e50..0aaa647e0 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of Solar Array Panel */ -#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ -#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ +#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ +#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ #include #include @@ -129,4 +129,4 @@ class SAP : public ComponentBase, public ILoggable { void MainRoutine(int time_count) override; }; -#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_H_ +#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/propulsion/initialize_simple_thruster.hpp b/src/components/propulsion/initialize_simple_thruster.hpp index e2b4419aa..55736928a 100644 --- a/src/components/propulsion/initialize_simple_thruster.hpp +++ b/src/components/propulsion/initialize_simple_thruster.hpp @@ -3,8 +3,8 @@ * @brief Initialize function os SimpleThruster */ -#ifndef S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ -#define S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ +#ifndef S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ +#define S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ #include @@ -32,4 +32,4 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_H_ +#endif // S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 67593a6ea..0b23787be 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of simple thruster */ -#ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ -#define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ +#ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ +#define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ #include #include @@ -152,4 +152,4 @@ class SimpleThruster : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_H_ +#endif // S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index c6be61ce4..fd49a3551 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -3,8 +3,8 @@ * @brief Abstract class for a disturbance which generate acceleration only (not force) */ -#ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ -#define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ +#ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ +#define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ #include "../dynamics/dynamics.hpp" #include "../environment/local/local_environment.hpp" @@ -42,4 +42,4 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; }; -#endif // S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_H_ +#endif // S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 0b7cb0f01..ad4c394d3 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate the air drag disturbance force and torque */ -#ifndef S2E_DISTURBANCES_AIR_DRAG_H_ -#define S2E_DISTURBANCES_AIR_DRAG_H_ +#ifndef S2E_DISTURBANCES_AIR_DRAG_HPP_ +#define S2E_DISTURBANCES_AIR_DRAG_HPP_ #include #include @@ -87,4 +87,4 @@ class AirDrag : public SurfaceForce { double funcChi(double s); }; -#endif // S2E_DISTURBANCES_AIR_DRAG_H_ +#endif // S2E_DISTURBANCES_AIR_DRAG_HPP_ diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index a2a845428..67f14e8b9 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -3,8 +3,8 @@ * @brief Base class for a disturbance */ -#ifndef S2E_DISTURBANCES_DISTURBANCE_H_ -#define S2E_DISTURBANCES_DISTURBANCE_H_ +#ifndef S2E_DISTURBANCES_DISTURBANCE_HPP_ +#define S2E_DISTURBANCES_DISTURBANCE_HPP_ #include "../library/math/vector.hpp" using libra::Vector; @@ -56,4 +56,4 @@ class Disturbance { Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] }; -#endif // S2E_DISTURBANCES_DISTURBANCE_H_ +#endif // S2E_DISTURBANCES_DISTURBANCE_HPP_ diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 1deaf2cbd..5985461ff 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -3,8 +3,8 @@ * @brief Class to manage all disturbances */ -#ifndef S2E_DISTURBANCES_DISTURBANCES_H_ -#define S2E_DISTURBANCES_DISTURBANCES_H_ +#ifndef S2E_DISTURBANCES_DISTURBANCES_HPP_ +#define S2E_DISTURBANCES_DISTURBANCES_HPP_ #include @@ -85,4 +85,4 @@ class Disturbances { void InitializeAcceleration(); }; -#endif // S2E_DISTURBANCES_DISTURBANCES_H_ +#endif // S2E_DISTURBANCES_DISTURBANCES_HPP_ diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 63902e60c..f1801626e 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate the high-order earth gravity acceleration */ -#ifndef S2E_DISTURBANCES_GEOPOTENTIAL_H_ -#define S2E_DISTURBANCES_GEOPOTENTIAL_H_ +#ifndef S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ +#define S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ #include @@ -87,4 +87,4 @@ class GeoPotential : public AccelerationDisturbance { double time_ = 0.0; //!< Calculation time [ms] }; -#endif // S2E_DISTURBANCES_GEOPOTENTIAL_H_ +#endif // S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index a4c8d57fc..264c82ddc 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate the gravity gradient torque */ -#ifndef S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ -#define S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ +#ifndef S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ +#define S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ #include @@ -66,4 +66,4 @@ class GravityGradient : public SimpleDisturbance { double mu_m3_s2_; //!< Gravitational constant [m3/s2] }; -#endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_H_ +#endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index b85ea823f..7bb8481fb 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -3,8 +3,8 @@ * @brief Define initialize functions for disturbances */ -#ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ -#define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ +#ifndef S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_HPP_ +#define S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_HPP_ #include #include @@ -65,4 +65,4 @@ GeoPotential InitGeoPotential(std::string ini_path); */ ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes); -#endif // S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_H_ +#endif // S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_HPP_ diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 49d29434c..2ad262103 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate the magnetic disturbance torque */ -#ifndef S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ -#define S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ +#ifndef S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ +#define S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ #include @@ -68,4 +68,4 @@ class MagDisturbance : public SimpleDisturbance { const RMMParams& rmm_params_; //!< RMM parameters }; -#endif // S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_H_ +#endif // S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 4e72a5e43..d541b4fe2 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -5,8 +5,8 @@ * In the difficult case, users need to use the Disturbance class directory. */ -#ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ -#define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ +#ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ +#define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ #include "../dynamics/dynamics.hpp" #include "../environment/local/local_environment.hpp" @@ -44,4 +44,4 @@ class SimpleDisturbance : public Disturbance, public ILoggable { virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; }; -#endif // S2E_DISTURBANCES_SIMPLE_DISTURBANCE_H_ +#endif // S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 6bf158ab3..e415752f1 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate the solar radiation pressure disturbance force and torque */ -#ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ -#define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ +#ifndef S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ +#define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ #include #include @@ -54,4 +54,4 @@ class SolarRadiation : public SurfaceForce { virtual void CalcCoef(Vector<3>& input_b, double item); }; -#endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_H_ +#endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 470a1ccdb..0cba65d36 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -5,8 +5,8 @@ #pragma once -#ifndef S2E_DISTURBANCES_SURFACE_FORCE_H_ -#define S2E_DISTURBANCES_SURFACE_FORCE_H_ +#ifndef S2E_DISTURBANCES_SURFACE_FORCE_HPP_ +#define S2E_DISTURBANCES_SURFACE_FORCE_HPP_ #include "../library/math/quaternion.hpp" #include "../library/math/vector.hpp" @@ -70,4 +70,4 @@ class SurfaceForce : public SimpleDisturbance { virtual void CalcCoef(Vector<3>& input_b, double item) = 0; }; -#endif // S2E_DISTURBANCES_SURFACE_FORCE_H_ +#endif // S2E_DISTURBANCES_SURFACE_FORCE_HPP_ diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 6e5026749..ef067fc40 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate third body gravity disturbance */ -#ifndef S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ -#define S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ +#ifndef S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ +#define S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ #include #include @@ -64,4 +64,4 @@ class ThirdBodyGravity : public AccelerationDisturbance { libra::Vector<3> thirdbody_acc_i_{0}; //!< Calculated third body disturbance acceleration in the inertial frame [m/s2] }; -#endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_H_ +#endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 6f133f6d9..3b2295203 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -3,8 +3,8 @@ * @brief Base class for attitude of spacecraft */ -#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ -#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ +#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ +#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ #include #include @@ -177,4 +177,4 @@ class Attitude : public ILoggable, public SimulationObject { void CalcSatRotationalKineticEnergy(void); }; -#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_H_ +#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index 355463bd9..88600bf1d 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate spacecraft attitude with Runge-Kutta method */ -#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ -#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ +#ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_HPP_ +#define S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_HPP_ #include "attitude.hpp" @@ -83,4 +83,4 @@ class AttitudeRK4 : public Attitude { void RungeOneStep(double t, double dt); }; -#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_H_ +#endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_HPP_ diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 54044c660..ec02f6122 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate spacecraft attitude with Controlled Attitude mode */ -#ifndef S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ -#define S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ +#ifndef S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ +#define S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ #include #include @@ -142,4 +142,4 @@ class ControlledAttitude : public Attitude { Matrix<3, 3> CalcDCM(const Vector<3> main_direction, const Vector<3> sub_direction); }; -#endif // S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_H_ +#endif // S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ diff --git a/src/dynamics/attitude/initialize_attitude.hpp b/src/dynamics/attitude/initialize_attitude.hpp index cae91bb09..dbe34e786 100644 --- a/src/dynamics/attitude/initialize_attitude.hpp +++ b/src/dynamics/attitude/initialize_attitude.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for attitude */ -#ifndef S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ -#define S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ +#ifndef S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_HPP_ +#define S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_HPP_ #include "attitude.hpp" #include "attitude_rk4.hpp" @@ -23,4 +23,4 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id); -#endif // S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_H_ +#endif // S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_HPP_ diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 8e5b9fdae..a8be22e9b 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -2,8 +2,8 @@ * @file dynamics.hpp * @brief Class to manage dynamics of spacecraft */ -#ifndef S2E_DYNAMICS_DYNAMICS_H_ -#define S2E_DYNAMICS_DYNAMICS_H_ +#ifndef S2E_DYNAMICS_DYNAMICS_HPP_ +#define S2E_DYNAMICS_DYNAMICS_HPP_ #include @@ -138,4 +138,4 @@ class Dynamics { const Structure* structure_; //!< Structure information }; -#endif // S2E_DYNAMICS_DYNAMICS_H_ +#endif // S2E_DYNAMICS_DYNAMICS_HPP_ diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 100447717..81807883b 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -3,8 +3,8 @@ * @brief Class to propagate spacecraft orbit with Encke's method */ -#ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ -#define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ +#ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ +#define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ #include "../../library/orbit/kepler_orbit.hpp" #include "../../library/math/ordinary_differential_equation.hpp" @@ -92,4 +92,4 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { double CalcQFunction(Vector<3> diff_pos_i); }; -#endif // S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_H_ +#endif // S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index 515235859..3784dc8ad 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for Orbit class */ -#ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ -#define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ +#ifndef S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ +#define S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ #include @@ -36,4 +36,4 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d */ Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3_s2, std::string section = "ORBIT"); -#endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_H_ +#endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index ef3895928..bf790ebec 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -3,8 +3,8 @@ * @brief Class to propagate spacecraft orbit with Kepler equation */ -#ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ -#define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ +#ifndef S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_HPP_ +#define S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_HPP_ #include "../../library/orbit/kepler_orbit.hpp" #include "orbit.hpp" @@ -48,4 +48,4 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { void UpdateState(const double current_jd); }; -#endif // S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_H_ +#endif // S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_HPP_ diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 2e1c1ebbb..06f6b5e51 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -3,8 +3,8 @@ * @brief Base class of orbit propagation */ -#ifndef S2E_DYNAMICS_ORBIT_ORBIT_H_ -#define S2E_DYNAMICS_ORBIT_ORBIT_H_ +#ifndef S2E_DYNAMICS_ORBIT_ORBIT_HPP_ +#define S2E_DYNAMICS_ORBIT_ORBIT_HPP_ #include #include @@ -227,4 +227,4 @@ class Orbit : public ILoggable { OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode); -#endif // S2E_DYNAMICS_ORBIT_ORBIT_H_ +#endif // S2E_DYNAMICS_ORBIT_ORBIT_HPP_ diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index f2cd0a562..7a6d7e841 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -3,8 +3,8 @@ * @brief Class to propagate relative orbit */ -#ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ -#define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ +#ifndef S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_HPP_ +#define S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_HPP_ #include #include @@ -124,4 +124,4 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { void PropagateSTM(double elapsed_sec); }; -#endif // S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_H_ +#endif // S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_HPP_ diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index eee6fcc31..b833cc102 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -3,8 +3,8 @@ * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -#ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ -#define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ +#ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ +#define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ #include #include @@ -80,4 +80,4 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { void Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); }; -#endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_H_ +#endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index aa6c29463..7ddd177ae 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -3,8 +3,8 @@ * @brief Class to propagate spacecraft orbit with SGP4 method with TLE */ -#ifndef S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ -#define S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ +#ifndef S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ +#define S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ #include #include @@ -52,4 +52,4 @@ class Sgp4OrbitPropagation : public Orbit { const CelestialInformation* celes_info_; //!< Celestial information }; -#endif // S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_H_ +#endif // S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ diff --git a/src/dynamics/thermal/initialize_node.hpp b/src/dynamics/thermal/initialize_node.hpp index 58eb0eed9..b4388b9e8 100644 --- a/src/dynamics/thermal/initialize_node.hpp +++ b/src/dynamics/thermal/initialize_node.hpp @@ -3,11 +3,11 @@ * @brief Initialize function for node */ -#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ -#define S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ +#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_HPP_ +#define S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_HPP_ #include "node.hpp" Node InitNode(const std::vector& node_str); -#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_H_ +#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_NODE_HPP_ diff --git a/src/dynamics/thermal/initialize_temperature.hpp b/src/dynamics/thermal/initialize_temperature.hpp index bd76de01b..a8f8792b6 100644 --- a/src/dynamics/thermal/initialize_temperature.hpp +++ b/src/dynamics/thermal/initialize_temperature.hpp @@ -3,12 +3,12 @@ * @brief Initialize function for temperature */ -#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ -#define S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ +#ifndef S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_HPP_ +#define S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_HPP_ #include "temperature.hpp" class Temperature; Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec); -#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_H_ +#endif // S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_HPP_ diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index 0c9b9a431..ee5eb96b1 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -3,8 +3,8 @@ * @brief thermal calculation node */ -#ifndef S2E_DYNAMICS_THERMAL_NODE_H_ -#define S2E_DYNAMICS_THERMAL_NODE_H_ +#ifndef S2E_DYNAMICS_THERMAL_NODE_HPP_ +#define S2E_DYNAMICS_THERMAL_NODE_HPP_ #include #include @@ -51,4 +51,4 @@ class Node { void PrintParam(void); }; -#endif // S2E_DYNAMICS_THERMAL_NODE_H_ +#endif // S2E_DYNAMICS_THERMAL_NODE_HPP_ diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 1f27adc98..29bb929ee 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -3,8 +3,8 @@ * @brief Initialize temperature */ -#ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ -#define S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ +#ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_HPP_ +#define S2E_DYNAMICS_THERMAL_TEMPERATURE_HPP_ #include #include @@ -41,4 +41,4 @@ class Temperature : public ILoggable { void PrintParams(void); // デバッグ出力 }; -#endif // S2E_DYNAMICS_THERMAL_TEMPERATURE_H_ +#endif // S2E_DYNAMICS_THERMAL_TEMPERATURE_HPP_ diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index a3155a4ee..cdee27e46 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -4,8 +4,8 @@ * @details This class uses SPICE to get the information of celestial bodies */ -#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ -#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ #include #include @@ -199,4 +199,4 @@ class CelestialInformation : public ILoggable { void GetPlanetOrbit(const char* planet_name, double et, double orbit[6]); }; -#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 5fda5d5a9..757f8a8fb 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -7,8 +7,8 @@ * IERS Conventions 2003 */ -#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ -#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ #include #include @@ -111,4 +111,4 @@ class CelestialRotation { const double kDayJulianCentury = 36525; //!< Conversion constant from Julian century to day [day/century] }; -#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 34d964367..8fd7e576d 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -3,8 +3,8 @@ * @brief Class to generate clock for classes which have ITickable */ -#ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ -#define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ #include #include @@ -59,4 +59,4 @@ class ClockGenerator { int timer_count_; //!< Timer count TODO: consider size, unsigned }; -#endif // S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index c3fe1a2b9..7167b519b 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -3,8 +3,8 @@ * @brief Class to manage the global environment */ -#ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ -#define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ #include #include @@ -83,4 +83,4 @@ class GlobalEnvironment { GnssSatellites* gnss_satellites_; //!< GNSS satellites }; -#endif // S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 0eccffcb1..d380a66a6 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate GNSS satellite position and related states */ -#ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ -#define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_HPP_ #include #include @@ -509,4 +509,4 @@ class GnssSatellites : public ILoggable { #endif }; -#endif // S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_HPP_ diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 17e3a44a6..7c15d3a10 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -3,8 +3,8 @@ *@brief Class to calculate star direction with Hipparcos catalogue */ -#ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ -#define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ #include #include @@ -111,4 +111,4 @@ class HipparcosCatalogue : public ILoggable { std::string catalogue_path_; //!< Path to Hipparcos catalog file }; -#endif // S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ diff --git a/src/environment/global/initialize_global_environment.hpp b/src/environment/global/initialize_global_environment.hpp index fc1619577..43446a516 100644 --- a/src/environment/global/initialize_global_environment.hpp +++ b/src/environment/global/initialize_global_environment.hpp @@ -3,8 +3,8 @@ *@brief Initialize functions for classes in global environment */ -#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ -#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_HPP_ #include #include @@ -31,4 +31,4 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name); */ CelestialInformation* InitCelesInfo(std::string file_name); -#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_HPP_ diff --git a/src/environment/global/initialize_gnss_satellites.hpp b/src/environment/global/initialize_gnss_satellites.hpp index f7b215fe6..ca55e995d 100644 --- a/src/environment/global/initialize_gnss_satellites.hpp +++ b/src/environment/global/initialize_gnss_satellites.hpp @@ -3,8 +3,8 @@ *@brief Initialize functions for GnssSatellites class */ -#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ -#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_HPP_ #include @@ -15,4 +15,4 @@ */ GnssSatellites* InitGnssSatellites(std::string file_name); -#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GNSS_SATELLITES_HPP_ diff --git a/src/environment/global/physical_constants.hpp b/src/environment/global/physical_constants.hpp index 28305190a..8c2581e0e 100644 --- a/src/environment/global/physical_constants.hpp +++ b/src/environment/global/physical_constants.hpp @@ -3,8 +3,8 @@ * @brief header for physical constant values */ -#ifndef S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ -#define S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_HPP_ #include // std::is_floating_point_v @@ -39,4 +39,4 @@ DEFINE_PHYSICAL_CONSTANT(earth_flattening, 3.352797e-3L) / } // namespace environment -#endif // S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_PHYSICAL_CONSTANT_HPP_ diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 32c73ff9d..75a5df921 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -3,8 +3,8 @@ *@brief Class to manage simulation time related information */ -#ifndef S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ -#define S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ +#ifndef S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_HPP_ +#define S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_HPP_ #ifdef WIN32 #define _WINSOCKAPI_ // stops windows.h including winsock.h @@ -320,4 +320,4 @@ class SimTime : public ILoggable { */ void ConvJDtoCalndarDay(const double JD); }; -#endif // S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_H_ +#endif // S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_HPP_ diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index e61bca52f..8521305bb 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -4,8 +4,8 @@ */ #pragma once -#ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ -#define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ +#define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ #include @@ -113,4 +113,4 @@ class Atmosphere : public ILoggable { double AddNoise(double rho); }; -#endif // S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_H_ +#endif // S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 1cf7116e4..d5c0ffee5 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate magnetic field of the earth */ -#ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ -#define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ +#define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ #include using libra::Vector; @@ -85,4 +85,4 @@ class MagEnvironment : public ILoggable { void AddNoise(double* mag_i_array); }; -#endif // S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_H_ +#endif // S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index 4d0098f96..ee9ac6b73 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for local environment classes */ -#ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ -#define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ +#define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ #include #include @@ -30,4 +30,4 @@ SRPEnvironment InitSRPEnvironment(std::string ini_path, LocalCelestialInformatio */ Atmosphere InitAtmosphere(std::string ini_path); -#endif // S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_H_ +#endif // S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 899429ada..0eacfc4af 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -3,8 +3,8 @@ * @brief Class to manage celestial body information in the spacecraft body frame */ -#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ -#define S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ +#define S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ #include "../global/celestial_information.hpp" @@ -117,4 +117,4 @@ void Convert_i2b(const double* src_i, double* dst_b, const Quaternion q_i2b); */ void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const Quaternion q_i2b, const Vector<3> bodyrate_b); -#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_H_ +#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 38fdb1eef..271e4ee87 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -3,8 +3,8 @@ * @brief Class to manage local environments */ -#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ -#define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ +#define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ #include #include @@ -88,4 +88,4 @@ class LocalEnvironment { LocalCelestialInformation* celes_info_; //!< Celestial information }; -#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_H_ +#endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 5000a332c..f6005fdb3 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate Solar Radiation Pressure */ -#ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ -#define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ +#ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ +#define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ #include #include @@ -103,4 +103,4 @@ class SRPEnvironment : public ILoggable { void CalcShadowCoefficient(std::string shadow_source_name); }; -#endif // S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_H_ +#endif // S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index 3f9bf937e..d8fc9d0bc 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -5,8 +5,8 @@ * Reference: https://docs.microsoft.com/ja-jp/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 */ -#ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ -#define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ +#ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ +#define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ #include #include @@ -104,4 +104,4 @@ class ComPortInterface { msclr::gcroot rx_buf_; //!< RX Buffer }; -#endif // S2E_INTERFACE_HILS_COM_PORT_INTERFACE_H_ +#endif // S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ diff --git a/src/interface/hils/hils_port_manager.hpp b/src/interface/hils/hils_port_manager.hpp index 12aebdb67..5b20ae5cd 100644 --- a/src/interface/hils/hils_port_manager.hpp +++ b/src/interface/hils/hils_port_manager.hpp @@ -3,8 +3,8 @@ * @brief Class to manage COM ports for HILS test */ -#ifndef S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ -#define S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ +#ifndef S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ +#define S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ #ifdef USE_HILS #include "ports/hils_i2c_target_port.hpp" @@ -167,4 +167,4 @@ class HilsPortManager { #endif }; -#endif // S2E_INTERFACE_HILS_HILS_PORT_MANAGER_H_ +#endif // S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ diff --git a/src/interface/hils/ports/hils_i2c_target_port.hpp b/src/interface/hils/ports/hils_i2c_target_port.hpp index b00687363..46d45ded4 100644 --- a/src/interface/hils/ports/hils_i2c_target_port.hpp +++ b/src/interface/hils/ports/hils_i2c_target_port.hpp @@ -3,8 +3,8 @@ * @brief Class to control I2C-USB converter for the target(device) side from COM port */ -#ifndef S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ -#define S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ +#ifndef S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ +#define S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ #include @@ -107,4 +107,4 @@ class HilsI2cTargetPort : public HilsUartPort { std::map cmd_buffer_; }; -#endif // S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_H_ +#endif // S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ diff --git a/src/interface/hils/ports/hils_uart_port.hpp b/src/interface/hils/ports/hils_uart_port.hpp index 0981486b9..32bb443e6 100644 --- a/src/interface/hils/ports/hils_uart_port.hpp +++ b/src/interface/hils/ports/hils_uart_port.hpp @@ -6,8 +6,8 @@ * @note TODO :We need to clarify the difference with ComPortInterface */ -#ifndef S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ -#define S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ +#ifndef S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ +#define S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ #include #include @@ -111,4 +111,4 @@ class HilsUartPort { int DiscardOutBuffer(); }; -#endif // S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_H_ +#endif // S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index 963a6a34b..07676f3a3 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -3,8 +3,8 @@ * @brief Class to read and get parameters for the `ini` format file */ -#ifndef S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ -#define S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ +#ifndef S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ +#define S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ #define _CRT_SECURE_NO_WARNINGS @@ -169,4 +169,4 @@ void IniAccess::ReadVector(const char* section_name, const char* key_name, Vecto } } -#endif // S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_H_ +#endif // S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ diff --git a/src/interface/log_output/initialize_log.hpp b/src/interface/log_output/initialize_log.hpp index a80072e4e..4a9557dde 100644 --- a/src/interface/log_output/initialize_log.hpp +++ b/src/interface/log_output/initialize_log.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for Log output */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ -#define S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ +#ifndef S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ +#define S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ #include @@ -23,4 +23,4 @@ Logger* InitLog(std::string file_name); */ Logger* InitLogMC(std::string file_name, bool enable); -#endif // S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_H_ +#endif // S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ diff --git a/src/interface/log_output/log_utility.hpp b/src/interface/log_output/log_utility.hpp index 39354a66d..3487e92fa 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/interface/log_output/log_utility.hpp @@ -3,8 +3,8 @@ * @brief Utility functions to support logging for users */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ -#define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ +#define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ #include #include @@ -159,4 +159,4 @@ std::string WriteQuaternion(std::string name, std::string frame) { return str_tmp.str(); } -#endif // S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_H_ +#endif // S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ diff --git a/src/interface/log_output/loggable.hpp b/src/interface/log_output/loggable.hpp index b56cbdf27..ec6da480d 100644 --- a/src/interface/log_output/loggable.hpp +++ b/src/interface/log_output/loggable.hpp @@ -3,8 +3,8 @@ * @brief Abstract class to manage logging */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ -#define S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ +#define S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ #include @@ -34,4 +34,4 @@ class ILoggable { bool IsLogEnabled = true; //!< Log enable flag }; -#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_H_ +#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ diff --git a/src/interface/log_output/logger.hpp b/src/interface/log_output/logger.hpp index cdc5f09a0..c20644b06 100644 --- a/src/interface/log_output/logger.hpp +++ b/src/interface/log_output/logger.hpp @@ -3,8 +3,8 @@ * @brief Class to manage log output file */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ -#define S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ +#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ +#define S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ #define _CRT_SECURE_NO_WARNINGS @@ -130,4 +130,4 @@ void Logger::Enable(bool enable) { is_enabled_ = enable; } std::string Logger::GetLogPath() const { return directory_path_; } -#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGER_H_ +#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/interface/sils/ports/gpio_port.hpp index 0de8a12a7..80f07d47f 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/interface/sils/ports/gpio_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate GPIO(General Purpose Input and Output) port */ -#ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ -#define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ +#ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ +#define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ #include @@ -51,4 +51,4 @@ class GPIOPort { bool hl_state_; //!< GPIO High/Low state }; -#endif // S2E_INTERFACE_SILS_PORTS_GPIO_PORT_H_ +#endif // S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ diff --git a/src/interface/sils/ports/i2c_port.hpp b/src/interface/sils/ports/i2c_port.hpp index dabe4fc42..6ce75949e 100644 --- a/src/interface/sils/ports/i2c_port.hpp +++ b/src/interface/sils/ports/i2c_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port */ -#ifndef S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ -#define S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ +#ifndef S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ +#define S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ #include @@ -109,4 +109,4 @@ class I2CPort { std::map, unsigned char> cmd_buffer_; }; -#endif // S2E_INTERFACE_SILS_PORTS_I2C_PORT_H_ +#endif // S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ diff --git a/src/interface/sils/ports/power_port.hpp b/src/interface/sils/ports/power_port.hpp index 6488a9d02..a1c72b112 100644 --- a/src/interface/sils/ports/power_port.hpp +++ b/src/interface/sils/ports/power_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate electrical power port */ -#ifndef S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ -#define S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ +#ifndef S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ +#define S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ #include @@ -133,4 +133,4 @@ class PowerPort { void Initialize(void); }; -#endif // S2E_INTERFACE_SILS_PORTS_POWER_PORT_H_ +#endif // S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ diff --git a/src/interface/sils/ports/uart_port.hpp b/src/interface/sils/ports/uart_port.hpp index f5f012405..fe0676d9c 100644 --- a/src/interface/sils/ports/uart_port.hpp +++ b/src/interface/sils/ports/uart_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate UART communication port */ -#ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ -#define S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ +#ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ +#define S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ #include "../utility/ring_buffer.hpp" @@ -79,4 +79,4 @@ class SCIPort { RingBuffer* txb_; //!< Transmit buffer (OBC -> Component) }; -#endif // S2E_INTERFACE_SILS_PORTS_UART_PORT_H_ +#endif // S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ diff --git a/src/interface/sils/utility/ring_buffer.hpp b/src/interface/sils/utility/ring_buffer.hpp index c98b09ba1..fb468face 100644 --- a/src/interface/sils/utility/ring_buffer.hpp +++ b/src/interface/sils/utility/ring_buffer.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate ring buffer */ -#ifndef S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ -#define S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ +#ifndef S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ +#define S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ typedef unsigned char byte; @@ -52,4 +52,4 @@ class RingBuffer { int wp_; //!< Write pointer }; -#endif // S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_H_ +#endif // S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ diff --git a/src/library/geodesy/geodetic_position.hpp b/src/library/geodesy/geodetic_position.hpp index f4161ef9f..09da97ebc 100644 --- a/src/library/geodesy/geodetic_position.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -3,8 +3,8 @@ * @brief Class to mange geodetic position expression */ -#ifndef S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ -#define S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ +#ifndef S2E_LIBRARY_GEODESY_GEODETIC_POSITION_HPP_ +#define S2E_LIBRARY_GEODESY_GEODETIC_POSITION_HPP_ #include #include @@ -78,4 +78,4 @@ class GeodeticPosition { void CalcQuaternionXcxfToLtc(); }; -#endif // S2E_LIBRARY_GEODESY_GEODETIC_POSITION_H_ \ No newline at end of file +#endif // S2E_LIBRARY_GEODESY_GEODETIC_POSITION_HPP_ \ No newline at end of file diff --git a/src/library/math/constants.hpp b/src/library/math/constants.hpp index 637b9ae5b..04bcc7dcd 100644 --- a/src/library/math/constants.hpp +++ b/src/library/math/constants.hpp @@ -3,8 +3,8 @@ * @brief header for math constant values */ -#ifndef S2E_LIBRARY_MATH_CONSTANTS_H_ -#define S2E_LIBRARY_MATH_CONSTANTS_H_ +#ifndef S2E_LIBRARY_MATH_CONSTANTS_HPP_ +#define S2E_LIBRARY_MATH_CONSTANTS_HPP_ #include // std::is_floating_point_v @@ -45,4 +45,4 @@ DEFINE_MATH_CONSTANT(arcsec_to_rad, deg_to_rad / 3600.0L) /* arcsecond to radian } // namespace libra -#endif // S2E_LIBRARY_MATH_CONSTANTS_H_ +#endif // S2E_LIBRARY_MATH_CONSTANTS_HPP_ diff --git a/src/library/math/global_randomization.hpp b/src/library/math/global_randomization.hpp index 02f3733f5..0f230e146 100644 --- a/src/library/math/global_randomization.hpp +++ b/src/library/math/global_randomization.hpp @@ -3,8 +3,8 @@ * @brief Class to manage global randomization */ -#ifndef S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ -#define S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ +#ifndef S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ +#define S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ #include "./randomize0.hpp" @@ -39,4 +39,4 @@ class GlobalRand { extern GlobalRand g_rand; //!< Global randomization -#endif // S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_H_ +#endif // S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 0dd5417cf..bce57182b 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef S2E_LIBRARY_MATH_MATRIX_H_ -#define S2E_LIBRARY_MATH_MATRIX_H_ +#ifndef S2E_LIBRARY_MATH_MATRIX_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_HPP_ #include // for size_t #include // for ostream, cout @@ -256,4 +256,4 @@ Matrix rotz(const double& theta); #include "matrix_ifs.hpp" // inline function definisions. #include "matrix_tfs.hpp" // template function definisions. -#endif // S2E_LIBRARY_MATH_MATRIX_H_ +#endif // S2E_LIBRARY_MATH_MATRIX_HPP_ diff --git a/src/library/math/matrix_ifs.hpp b/src/library/math/matrix_ifs.hpp index b3856a38b..aa646689f 100644 --- a/src/library/math/matrix_ifs.hpp +++ b/src/library/math/matrix_ifs.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef S2E_LIBRARY_MATH_MATRIX_IFS_H_ -#define S2E_LIBRARY_MATH_MATRIX_IFS_H_ +#ifndef S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ #include // for invalid_argument @@ -56,4 +56,4 @@ bool Matrix::is_valid_range_(size_t row, size_t column) { } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_IFS_H_ +#endif // S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ diff --git a/src/library/math/matrix_tfs.hpp b/src/library/math/matrix_tfs.hpp index a61283993..957928914 100644 --- a/src/library/math/matrix_tfs.hpp +++ b/src/library/math/matrix_tfs.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef S2E_LIBRARY_MATH_MATRIX_TFS_H_ -#define S2E_LIBRARY_MATH_MATRIX_TFS_H_ +#ifndef S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ #include #include // for cout @@ -192,4 +192,4 @@ Matrix rotz(const double& theta) { } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_TFS_H_ +#endif // S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ diff --git a/src/library/math/matrix_vector.hpp b/src/library/math/matrix_vector.hpp index bd4d59b46..ae03f235f 100644 --- a/src/library/math/matrix_vector.hpp +++ b/src/library/math/matrix_vector.hpp @@ -3,8 +3,8 @@ * @brief Template library for Matrix-Vector calculation */ -#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_H_ -#define S2E_LIBRARY_MATH_MATRIX_VECTOR_H_P +#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_P #include "vector.hpp" #include "matrix.hpp" @@ -56,4 +56,4 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& #include "matrix_vector_impl.hpp" -#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_H_ +#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_ diff --git a/src/library/math/matrix_vector_impl.hpp b/src/library/math/matrix_vector_impl.hpp index 202fc4023..30688961b 100644 --- a/src/library/math/matrix_vector_impl.hpp +++ b/src/library/math/matrix_vector_impl.hpp @@ -3,8 +3,8 @@ * @brief Template library for Matrix-Vector calculation */ -#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ -#define S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ +#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ #include // for invalid_argument. @@ -141,4 +141,4 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_H_ +#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ diff --git a/src/library/math/normal_randomization.hpp b/src/library/math/normal_randomization.hpp index 9fdfd9677..ab074b27f 100644 --- a/src/library/math/normal_randomization.hpp +++ b/src/library/math/normal_randomization.hpp @@ -4,8 +4,8 @@ * @note Ref: NUMERICAL RECIPES in C, p.216-p.217 */ -#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ -#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ +#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ +#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ #include "randomize1.hpp" using libra::Ran1; @@ -103,4 +103,4 @@ class NormalRand { #include "normal_randomization_ifs.hpp" // inline function definisions. -#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_H_ +#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ diff --git a/src/library/math/normal_randomization_ifs.hpp b/src/library/math/normal_randomization_ifs.hpp index 29b5492d4..fd95f7f96 100644 --- a/src/library/math/normal_randomization_ifs.hpp +++ b/src/library/math/normal_randomization_ifs.hpp @@ -3,8 +3,8 @@ * @brief Class to generate random value with normal distribution with Box-Muller method * @note Inline functions */ -#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ -#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ +#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ +#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ namespace libra { @@ -29,4 +29,4 @@ void NormalRand::set_param(double avg, double stddev, long seed) { } // namespace libra -#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_H_ +#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 57cc69b8b..f3e35f1a9 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -3,8 +3,8 @@ * @brief Class for Ordinary Difference Equation */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ #include "./vector.hpp" @@ -114,4 +114,4 @@ class ODE { #include "./ordinary_differential_equation_ifs.hpp" // inline function definisions. #include "./ordinary_differential_equation_tfs.hpp" // template function definisions. -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_H_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ diff --git a/src/library/math/ordinary_differential_equation_ifs.hpp b/src/library/math/ordinary_differential_equation_ifs.hpp index 3fe09c945..60ebef3b6 100644 --- a/src/library/math/ordinary_differential_equation_ifs.hpp +++ b/src/library/math/ordinary_differential_equation_ifs.hpp @@ -3,8 +3,8 @@ * @brief Class for Ordinary Difference Equation (inline functions) */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ namespace libra { @@ -43,4 +43,4 @@ libra::Vector& ODE::state() { } // namespace libra -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_H_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ diff --git a/src/library/math/ordinary_differential_equation_impl.hpp b/src/library/math/ordinary_differential_equation_impl.hpp index 829f1fd57..404f68e18 100644 --- a/src/library/math/ordinary_differential_equation_impl.hpp +++ b/src/library/math/ordinary_differential_equation_impl.hpp @@ -4,8 +4,8 @@ * @brief Class for Ordinary Difference Equation */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ namespace libra { @@ -43,4 +43,4 @@ ODE& ODE::operator++() { } // namespace libra -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_H_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ diff --git a/src/library/math/ordinary_differential_equation_tfs.hpp b/src/library/math/ordinary_differential_equation_tfs.hpp index ec56dd0f6..40643a218 100644 --- a/src/library/math/ordinary_differential_equation_tfs.hpp +++ b/src/library/math/ordinary_differential_equation_tfs.hpp @@ -2,8 +2,8 @@ * @file ordinary_differential_equation_tfs.hpp * @brief Class for Ordinary Difference Equation (template functions) */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ namespace libra { @@ -49,4 +49,4 @@ void ODE::setStepWidth(double new_step) { } } // namespace libra -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_H_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ diff --git a/src/library/math/quantization.hpp b/src/library/math/quantization.hpp index a47abea09..9ba1bdd06 100644 --- a/src/library/math/quantization.hpp +++ b/src/library/math/quantization.hpp @@ -3,8 +3,8 @@ * @brief Functions for quantization */ -#ifndef S2E_LIBRARY_MATH_QUANTIZATION_H_ -#define S2E_LIBRARY_MATH_QUANTIZATION_H_ +#ifndef S2E_LIBRARY_MATH_QUANTIZATION_HPP_ +#define S2E_LIBRARY_MATH_QUANTIZATION_HPP_ /** * @fn quantization @@ -24,4 +24,4 @@ double quantization(double continuous_num, double resolution); */ float quantization_f(double continuous_num, double resolution); -#endif // S2E_LIBRARY_MATH_QUANTIZATION_H_ +#endif // S2E_LIBRARY_MATH_QUANTIZATION_HPP_ diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index c7e983648..8fceae5d8 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -3,8 +3,8 @@ * @brief Class for Quaternion */ -#ifndef S2E_LIBRARY_MATH_QUATERNION_H_ -#define S2E_LIBRARY_MATH_QUATERNION_H_ +#ifndef S2E_LIBRARY_MATH_QUATERNION_HPP_ +#define S2E_LIBRARY_MATH_QUATERNION_HPP_ #include "vector.hpp" #include "matrix.hpp" @@ -209,4 +209,4 @@ Quaternion operator*(const double& lhs, const Quaternion& rhs); #include "quaternion_ifs.hpp" // inline function definisions. -#endif // S2E_LIBRARY_MATH_QUATERNION_H_ +#endif // S2E_LIBRARY_MATH_QUATERNION_HPP_ diff --git a/src/library/math/quaternion_ifs.hpp b/src/library/math/quaternion_ifs.hpp index 65689d5d7..f026ddf70 100644 --- a/src/library/math/quaternion_ifs.hpp +++ b/src/library/math/quaternion_ifs.hpp @@ -3,8 +3,8 @@ * @brief Class for Quaternion (Inline functions) */ -#ifndef S2E_LIBRARY_MATH_QUATERNION_IFS_H_ -#define S2E_LIBRARY_MATH_QUATERNION_IFS_H_ +#ifndef S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ +#define S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ namespace libra { @@ -32,4 +32,4 @@ Quaternion::operator const Vector<4>&() const { return q_; } } // namespace libra -#endif // S2E_LIBRARY_MATH_QUATERNION_IFS_H_ +#endif // S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ diff --git a/src/library/math/random_walk.hpp b/src/library/math/random_walk.hpp index 54a3d5b92..93fed2800 100644 --- a/src/library/math/random_walk.hpp +++ b/src/library/math/random_walk.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate random wark value */ -#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_H_ -#define S2E_LIBRARY_MATH_RANDOM_WALK_H_ +#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ +#define S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ #include "./vector.hpp" #include "./normal_randomization.hpp" @@ -42,4 +42,4 @@ class RandomWalk : public libra::ODE { #include "./random_walk_tfs.hpp" // template function definisions. -#endif // S2E_LIBRARY_MATH_RANDOM_WALK_H_ \ No newline at end of file +#endif // S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ \ No newline at end of file diff --git a/src/library/math/random_walk_tfs.hpp b/src/library/math/random_walk_tfs.hpp index 523f09997..d9613efb1 100644 --- a/src/library/math/random_walk_tfs.hpp +++ b/src/library/math/random_walk_tfs.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate random wark value (template functions) */ -#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_TFS_H_ -#define S2E_LIBRARY_MATH_RANDOM_WALK_TFS_H_ +#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ +#define S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ #include #include @@ -32,4 +32,4 @@ void RandomWalk::RHS(double x, const libra::Vector& state, libra::Vector // size_t @@ -61,4 +61,4 @@ class Ran1 { } // namespace libra -#endif // S2E_LIBRARY_MATH_RANDOMIZE1_H_ +#endif // S2E_LIBRARY_MATH_RANDOMIZE1_HPP_ diff --git a/src/library/math/s2e_math.hpp b/src/library/math/s2e_math.hpp index b5b3ebddb..175f2072d 100644 --- a/src/library/math/s2e_math.hpp +++ b/src/library/math/s2e_math.hpp @@ -3,8 +3,8 @@ * @brief Math functions */ -#ifndef S2E_LIBRARY_MATH_S2E_MATH_H_ -#define S2E_LIBRARY_MATH_S2E_MATH_H_ +#ifndef S2E_LIBRARY_MATH_S2E_MATH_HPP_ +#define S2E_LIBRARY_MATH_S2E_MATH_HPP_ #include @@ -19,4 +19,4 @@ double WrapTo2Pi(const double angle); } // namespace libra -#endif // S2E_LIBRARY_MATH_S2E_MATH_H_ +#endif // S2E_LIBRARY_MATH_S2E_MATH_HPP_ diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 28889abdf..987146f24 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -3,8 +3,8 @@ * @brief Class for mathematical vector */ -#ifndef S2E_LIBRARY_MATH_VECTOR_H_ -#define S2E_LIBRARY_MATH_VECTOR_H_ +#ifndef S2E_LIBRARY_MATH_VECTOR_HPP_ +#define S2E_LIBRARY_MATH_VECTOR_HPP_ #include // for size_t #include // for ostream, cout @@ -248,4 +248,4 @@ Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v); #include "vector_ifs.hpp" // inline function definisions. #include "vector_tfs.hpp" // template function definisions. -#endif // S2E_LIBRARY_MATH_VECTOR_H_ +#endif // S2E_LIBRARY_MATH_VECTOR_HPP_ diff --git a/src/library/math/vector_ifs.hpp b/src/library/math/vector_ifs.hpp index 54fe6fbe1..ec8b197c0 100644 --- a/src/library/math/vector_ifs.hpp +++ b/src/library/math/vector_ifs.hpp @@ -3,8 +3,8 @@ * @brief Class for mathematical vector (inline functions) */ -#ifndef S2E_LIBRARY_MATH_VECTOR_IFS_H_ -#define S2E_LIBRARY_MATH_VECTOR_IFS_H_ +#ifndef S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ +#define S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ #include // for invalid_argument. @@ -46,4 +46,4 @@ T Vector::operator()(std::size_t pos) const { } // namespace libra -#endif // S2E_LIBRARY_MATH_VECTOR_IFS_H_ +#endif // S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ diff --git a/src/library/math/vector_tfs.hpp b/src/library/math/vector_tfs.hpp index 0f808b776..fe4798bed 100644 --- a/src/library/math/vector_tfs.hpp +++ b/src/library/math/vector_tfs.hpp @@ -3,8 +3,8 @@ * @brief Class for mathematical vector (template functions) */ -#ifndef S2E_LIBRARY_MATH_VECTOR_TFS_H_ -#define S2E_LIBRARY_MATH_VECTOR_TFS_H_ +#ifndef S2E_LIBRARY_MATH_VECTOR_TFS_HPP_ +#define S2E_LIBRARY_MATH_VECTOR_TFS_HPP_ #include @@ -146,4 +146,4 @@ double angle(const Vector& v1, const Vector& v2) { } // namespace libra -#endif // S2E_LIBRARY_MATH_VECTOR_TFS_H_ +#endif // S2E_LIBRARY_MATH_VECTOR_TFS_HPP_ diff --git a/src/library/nrlmsise00/wrapper_nrlmsise00.hpp b/src/library/nrlmsise00/wrapper_nrlmsise00.hpp index 44af765cf..e1f3ac39f 100644 --- a/src/library/nrlmsise00/wrapper_nrlmsise00.hpp +++ b/src/library/nrlmsise00/wrapper_nrlmsise00.hpp @@ -3,8 +3,8 @@ * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ -#ifndef S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ -#define S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ +#ifndef S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ +#define S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ #include #include @@ -74,4 +74,4 @@ int GetSpaceWeatherTable_(double decyear, double endsec, const std::string& file #define __inline_double double #endif -#endif // S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__H_ +#endif // S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ diff --git a/src/library/optics/gaussian_beam_base.hpp b/src/library/optics/gaussian_beam_base.hpp index 2827a4cd1..5d56375d4 100644 --- a/src/library/optics/gaussian_beam_base.hpp +++ b/src/library/optics/gaussian_beam_base.hpp @@ -3,8 +3,8 @@ * @brief Class to express gaussian beam laser */ -#ifndef S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ -#define S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ +#ifndef S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_HPP_ +#define S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_HPP_ #include "../math/vector.hpp" @@ -107,4 +107,4 @@ class GaussianBeamBase { libra::Vector<3> pos_beamwaist_i_{0.0}; //!< Position of beam waist in the inertial frame [m] (Not used?) }; -#endif // S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_H_ +#endif // S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_HPP_ diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 52c912678..30b4259a2 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate Kepler orbit calculation */ -#ifndef S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ -#define S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ +#ifndef S2E_LIBRARY_ORBIT_KEPLER_ORBIT_HPP_ +#define S2E_LIBRARY_ORBIT_KEPLER_ORBIT_HPP_ #include "../math/matrix.hpp" #include "../math/vector.hpp" @@ -78,4 +78,4 @@ class KeplerOrbit { double SolveKeplerFirstOrder(const double eccentricity, const double mean_anomaly_rad, const double angle_limit_rad, const int iteration_limit); }; -#endif // S2E_LIBRARY_ORBIT_KEPLER_ORBIT_H_ +#endif // S2E_LIBRARY_ORBIT_KEPLER_ORBIT_HPP_ diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index 92a4991f5..d78d424d8 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -3,8 +3,8 @@ * @brief Class for classical orbital elements */ -#ifndef S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ -#define S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ +#ifndef S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ +#define S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ #include "../math/vector.hpp" @@ -95,4 +95,4 @@ class OrbitalElements { void CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> r_i_m, const libra::Vector<3> v_i_m_s); }; -#endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_H_ +#endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index 67fb2d376..4db6cb79a 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -3,8 +3,8 @@ * @brief Functions for relative orbit */ -#ifndef S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ -#define S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ +#ifndef S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ +#define S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ #include "../math/matrix.hpp" #include "../math/vector.hpp" @@ -42,4 +42,4 @@ libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu); */ libra::Matrix<6, 6> CalculateHCWSTM(double orbit_radius, double mu, double elapsed_sec); -#endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_H_ +#endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ diff --git a/src/library/utilities/endian.h b/src/library/utilities/endian.h index a593e045c..cee86b6cf 100644 --- a/src/library/utilities/endian.h +++ b/src/library/utilities/endian.h @@ -3,8 +3,8 @@ * @brief Function to consider the endian */ -#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_H_ -#define S2E_LIBRARY_UTILITIES_ENDIAN_H_ +#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_HPP_ +#define S2E_LIBRARY_UTILITIES_ENDIAN_HPP_ #include #include @@ -20,4 +20,4 @@ */ void *endian_memcpy(void *dst, const void *src, size_t count); -#endif // S2E_LIBRARY_UTILITIES_ENDIAN_H_ \ No newline at end of file +#endif // S2E_LIBRARY_UTILITIES_ENDIAN_HPP_ \ No newline at end of file diff --git a/src/library/utilities/endian_define.hpp b/src/library/utilities/endian_define.hpp index bd2e5195b..5b1d9556d 100644 --- a/src/library/utilities/endian_define.hpp +++ b/src/library/utilities/endian_define.hpp @@ -3,8 +3,8 @@ * @brief Define macro to change the endian definition */ -#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ -#define S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ +#ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_HPP_ +#define S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_HPP_ #ifndef IS_LITTLE_ENDIAN @@ -12,4 +12,4 @@ #endif // IS_LITTLE_ENDIAN -#endif // #ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_H_ +#endif // #ifndef S2E_LIBRARY_UTILITIES_ENDIAN_DEFINE_HPP_ diff --git a/src/library/utilities/macros.hpp b/src/library/utilities/macros.hpp index a17c07572..308db3cd8 100644 --- a/src/library/utilities/macros.hpp +++ b/src/library/utilities/macros.hpp @@ -3,9 +3,9 @@ * @brief Definition of commonly used macros */ -#ifndef S2E_LIBRARY_UTILITIES_MACROS_H_ -#define S2E_LIBRARY_UTILITIES_MACROS_H_ +#ifndef S2E_LIBRARY_UTILITIES_MACROS_HPP_ +#define S2E_LIBRARY_UTILITIES_MACROS_HPP_ #define UNUSED(x) (void)(x) //!< Macro to avoid unused warnings -#endif // S2E_LIBRARY_UTILITIES_MACROS_H_ +#endif // S2E_LIBRARY_UTILITIES_MACROS_HPP_ diff --git a/src/library/utilities/slip.h b/src/library/utilities/slip.h index 602752b15..6ab5e4fe1 100644 --- a/src/library/utilities/slip.h +++ b/src/library/utilities/slip.h @@ -3,8 +3,8 @@ * @brief Functions for SLIP(Serial Line Internet Protocol) encoding */ -#ifndef S2E_LIBRARY_UTILITIES_SLIP_H_ -#define S2E_LIBRARY_UTILITIES_SLIP_H_ +#ifndef S2E_LIBRARY_UTILITIES_SLIP_HPP_ +#define S2E_LIBRARY_UTILITIES_SLIP_HPP_ #include @@ -40,4 +40,4 @@ std::vector encode_slip(std::vector in); */ std::vector encode_slip_with_header(std::vector in); -#endif // S2E_LIBRARY_UTILITIES_SLIP_H_ +#endif // S2E_LIBRARY_UTILITIES_SLIP_HPP_ diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index fec371cce..865259952 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -3,8 +3,8 @@ * @brief Base class to manage relative information between spacecraft */ -#ifndef S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ -#define S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ +#ifndef S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ +#define S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ #include @@ -171,4 +171,4 @@ class RelativeInformation : public ILoggable { void ResizeLists(); }; -#endif // S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_H_ +#endif // S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index bae948cfe..373a79ba0 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -3,8 +3,8 @@ * @brief Example of user defined simulation case */ -#ifndef S2E_SIMULATION_CASE_SAMPLE_CASE_H_ -#define S2E_SIMULATION_CASE_SAMPLE_CASE_H_ +#ifndef S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ +#define S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ #include "../ground_station/sample_ground_station/sample_ground_station.hpp" #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" @@ -56,4 +56,4 @@ class SampleCase : public SimulationCase { SampleGS* sample_gs_; //!< Instance of ground station }; -#endif // S2E_SIMULATION_CASE_SAMPLE_CASE_H_ +#endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 919146c0f..b96aaa2c7 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -3,8 +3,8 @@ * @brief Base class to define simulation scenario */ -#ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_H_ -#define S2E_SIMULATION_CASE_SIMULATION_CASE_H_ +#ifndef S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ +#define S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ #include #include @@ -75,4 +75,4 @@ class SimulationCase : public ILoggable { GlobalEnvironment* glo_env_; //!< Global Environment }; -#endif // S2E_SIMULATION_CASE_SIMULATION_CASE_H_ +#endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index ae0d0756f..6ad8bb569 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -3,8 +3,8 @@ * @brief Base class of ground station */ -#ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ -#define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ +#ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ +#define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ #include #include @@ -110,4 +110,4 @@ class GroundStation : public ILoggable { bool CalcIsVisible(const Vector<3> sc_pos_ecef_m); }; -#endif // S2E_SIMULATION_GROUND_STATION_GROUND_STATION_H_ +#endif // S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index b2c7a1fe3..d4cabce48 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -3,8 +3,8 @@ * @brief An example of user defined ground station class */ -#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ -#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ +#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ +#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ #include #include @@ -53,4 +53,4 @@ class SampleGS : public GroundStation { SampleGSComponents* components_; //!< Ground station related components }; -#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_H_ +#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index b725eb8ae..529a59421 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -3,8 +3,8 @@ * @brief An example of ground station related components list */ -#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ -#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ +#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ +#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ #include #include @@ -49,4 +49,4 @@ class SampleGSComponents { const SimulationConfig* config_; //!< Simulation setting }; -#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_H_ +#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp index 3a0cbeb6f..3e35dea15 100644 --- a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp +++ b/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp @@ -3,8 +3,8 @@ * @brief Base class of inter satellite communication */ -#ifndef S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ -#define S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ +#ifndef S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ +#define S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ #include "../simulation_configuration.hpp" @@ -28,4 +28,4 @@ class InterSatComm { private: }; -#endif // S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_H_ +#endif // S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index ed118160d..8e8fb8848 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -3,8 +3,8 @@ * @brief Initialized parameters for Monte-Carlo simulation */ -#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ -#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_HPP_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_HPP_ #include #include @@ -233,4 +233,4 @@ void InitParameter::GetVec(Vector& dst_vec) const { } } -#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_H_ +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_HPP_ diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp index e53d061a7..c667c9583 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for Monte-Carlo Simulator */ -#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ -#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_HPP_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_HPP_ #include "initialize_monte_carlo_parameters.hpp" #include "monte_carlo_simulation_executor.hpp" @@ -15,4 +15,4 @@ */ MCSimExecutor* InitMCSim(std::string file_name); -#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_H_ +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_HPP_ diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index af69eff8d..d795d8dd7 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -3,8 +3,8 @@ * @brief Monte-Carlo Simulation Executor class */ -#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ -#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_HPP_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_HPP_ #include #include @@ -176,4 +176,4 @@ void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, c } } -#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_H_ +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_MONTE_CARLO_SIMULATION_EXECUTOR_HPP_ diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 0550867ed..a1c39b8af 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -3,8 +3,8 @@ * @brief Class to manage randomization of variables for Monte-Carlo simulation */ -#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ -#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ +#ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ +#define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ #include #include @@ -81,4 +81,4 @@ void SimulationObject::GetInitParameterVec(const MCSimExecutor& mc_sim, std::str mc_sim.GetInitParameterVec(name_, ip_name, dst_vec); } -#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_H_ +#endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index f68187503..c54406b1e 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -3,8 +3,8 @@ * @brief Definition of struct for simulation setting information */ -#ifndef S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ -#define S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ +#ifndef S2E_SIMULATION_SIMULATION_CONFIGURATION_HPP_ +#define S2E_SIMULATION_SIMULATION_CONFIGURATION_HPP_ #include #include @@ -31,4 +31,4 @@ struct SimulationConfig { ~SimulationConfig() { delete main_logger_; } }; -#endif // S2E_SIMULATION_SIMULATION_CONFIGURATION_H_ +#endif // S2E_SIMULATION_SIMULATION_CONFIGURATION_HPP_ diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index 42e8cd524..eb1309291 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -3,8 +3,8 @@ * @brief Definition of InstalledComponents class */ -#ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ -#define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ +#define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ #include #include @@ -43,4 +43,4 @@ class InstalledComponents { virtual void LogSetup(Logger& logger); }; -#endif // S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_H_ +#endif // S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 03f6e2206..b3afa58ed 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -3,8 +3,8 @@ * @brief An example of user side components management installed on a spacecraft */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ #include #include @@ -118,4 +118,4 @@ class SampleComponents : public InstalledComponents { const GlobalEnvironment* glo_env_; //!< Global environment information }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_H_ +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp index 2454aa136..fb1ece1e6 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp @@ -3,8 +3,8 @@ * @brief An example of port configuration management */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ /** * @enum PowerPortConfig @@ -27,4 +27,4 @@ enum UARTPortConfig { UART_COMPONENT_MAX //!< Maximum port number. Do not remove. Place on the bottom. }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_H_ +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index 0f280c57b..561300a8e 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -3,8 +3,8 @@ * @brief An example of user side spacecraft class */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ +#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ #include "../spacecraft.hpp" #include "sample_components.hpp" @@ -33,4 +33,4 @@ class SampleSat : public Spacecraft { SampleComponents* sample_components_; }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_H_ +#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 5a3255995..7c6acccee 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -3,8 +3,8 @@ * @brief Definition of Spacecraft class */ -#ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ -#define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_SPACECRAFT_HPP_ +#define S2E_SIMULATION_SPACECRAFT_SPACECRAFT_HPP_ #include #include @@ -115,4 +115,4 @@ class Spacecraft { const int sat_id_; //!< ID of the spacecraft }; -#endif // S2E_SIMULATION_SPACECRAFT_SPACECRAFT_H_ +#endif // S2E_SIMULATION_SPACECRAFT_SPACECRAFT_HPP_ diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index 9849dd84c..e890d1992 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -3,8 +3,8 @@ * @brief Initialize functions for spacecraft structure */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_HPP_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_HPP_ #pragma once @@ -26,4 +26,4 @@ vector InitSurfaces(std::string ini_path); */ RMMParams InitRMMParams(std::string ini_path); -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_HPP_ diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index c82f10d21..0402773fb 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -3,8 +3,8 @@ * @brief Definition of Kinematics information */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_HPP_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_HPP_ #include #include @@ -86,4 +86,4 @@ class KinematicsParams { Matrix<3, 3> inertia_tensor_; //!< Inertia tensor at body frame [kgm2] }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_HPP_ diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index ff83b5c62..0f2979450 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -3,8 +3,8 @@ * @brief Definition of Residual Magnetic Moment (RMM) */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_HPP_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_HPP_ #include using libra::Vector; @@ -69,4 +69,4 @@ class RMMParams { double rmm_wnvar_; //!< Standard deviation of white noise of RMM [Am2] }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_H_ \ No newline at end of file +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_HPP_ \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 819251c92..558cd6e47 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -3,8 +3,8 @@ * @brief Definition of spacecraft structure */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ #include #include @@ -75,4 +75,4 @@ class Structure { RMMParams* rmm_params_; //!< Residual Magnetic Moment }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 169e33df5..2f15cba07 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -3,8 +3,8 @@ * @brief Definition of spacecraft surface */ -#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ -#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#ifndef S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_HPP_ +#define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_HPP_ #include using libra::Vector; @@ -116,4 +116,4 @@ class Surface { double air_specularity_; //!< Specularity for air drag }; -#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_H_ +#endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_HPP_ From 61b21761658e0b8a08895d8bcf9a1a7862356af3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:54:56 +0100 Subject: [PATCH 0366/1086] Fix format --- src/components/aocs/gnss_receiver.cpp | 3 +-- src/components/aocs/gnss_receiver.hpp | 4 ++-- src/components/aocs/magnetorquer.cpp | 3 +-- src/components/aocs/reaction_wheel.cpp | 4 ++-- src/components/aocs/star_sensor.cpp | 7 +++---- src/components/aocs/sun_sensor.cpp | 3 +-- src/components/communication/antenna.cpp | 2 +- src/components/communication/antenna_radiation_pattern.cpp | 2 +- src/components/communication/ground_station_calculator.cpp | 2 +- src/components/mission/telescope.cpp | 2 +- src/components/mission/telescope.hpp | 4 ++-- src/components/power/solar_array_panel.hpp | 2 +- src/components/propulsion/simple_thruster.cpp | 5 ++--- src/components/propulsion/simple_thruster.hpp | 4 ++-- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 4 ++-- src/disturbances/geopotential.hpp | 4 ++-- src/disturbances/gravity_gradient.hpp | 4 ++-- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.hpp | 2 +- src/dynamics/orbit/orbit.hpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 2 +- src/dynamics/thermal/temperature.cpp | 2 +- src/environment/global/celestial_information.hpp | 6 +++--- src/environment/global/celestial_rotation.cpp | 2 +- src/environment/global/celestial_rotation.hpp | 6 +++--- src/environment/global/gnss_satellites.cpp | 4 ++-- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.cpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/local/atmosphere.cpp | 3 +-- src/environment/local/atmosphere.hpp | 5 ++--- src/environment/local/geomagnetic_field.cpp | 4 ++-- .../local/solar_radiation_pressure_environment.cpp | 4 ++-- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/interface/initialize/initialize_file_access.hpp | 2 +- src/interface/log_output/log_utility.hpp | 2 +- src/library/geodesy/geodetic_position.cpp | 2 +- src/library/math/matrix_vector.hpp | 2 +- src/library/math/quaternion.hpp | 2 +- src/library/math/random_walk.hpp | 2 +- src/library/nrlmsise00/wrapper_nrlmsise00.cpp | 2 +- src/library/optics/gaussian_beam_base.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 4 ++-- src/simulation/ground_station/ground_station.hpp | 2 +- .../initialize_monte_carlo_parameters.hpp | 2 +- .../monte_carlo_simulation/simulation_object.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 2 +- .../spacecraft/structure/initialize_structure.cpp | 2 +- 58 files changed, 78 insertions(+), 85 deletions(-) diff --git a/src/components/aocs/gnss_receiver.cpp b/src/components/aocs/gnss_receiver.cpp index 3015260f3..6694810a9 100644 --- a/src/components/aocs/gnss_receiver.cpp +++ b/src/components/aocs/gnss_receiver.cpp @@ -5,9 +5,8 @@ #include "gnss_receiver.hpp" -#include - #include +#include #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 78ee19bdc..bd8913bec 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -6,12 +6,12 @@ #ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ #define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ -#include -#include #include #include #include #include +#include +#include #include "../base_classes/component_base.hpp" diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index f622d65e0..65a2065aa 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -5,11 +5,10 @@ #include "magnetorquer.hpp" +#include #include - #include #include -#include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, diff --git a/src/components/aocs/reaction_wheel.cpp b/src/components/aocs/reaction_wheel.cpp index a6e67fdff..7222b5eae 100644 --- a/src/components/aocs/reaction_wheel.cpp +++ b/src/components/aocs/reaction_wheel.cpp @@ -4,10 +4,10 @@ */ #include "reaction_wheel.hpp" -#include -#include #include #include +#include +#include #include using namespace libra; diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 467a8437c..30b0b60ea 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -5,12 +5,11 @@ #include "star_sensor.hpp" -#include - -#include -#include #include #include +#include +#include +#include #include using namespace std; diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index 087ee10dc..c2c49d006 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -8,9 +8,8 @@ #include #include using libra::NormalRand; -#include - #include +#include using namespace std; diff --git a/src/components/communication/antenna.cpp b/src/components/communication/antenna.cpp index ab2f4ab86..bb3d3c202 100644 --- a/src/components/communication/antenna.cpp +++ b/src/components/communication/antenna.cpp @@ -5,8 +5,8 @@ #include "antenna.hpp" -#include #include +#include Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) diff --git a/src/components/communication/antenna_radiation_pattern.cpp b/src/components/communication/antenna_radiation_pattern.cpp index abe805f84..999876691 100644 --- a/src/components/communication/antenna_radiation_pattern.cpp +++ b/src/components/communication/antenna_radiation_pattern.cpp @@ -5,9 +5,9 @@ #include "antenna_radiation_pattern.hpp" -#include #include #include +#include AntennaRadiationPattern::AntennaRadiationPattern() { gain_dBi_.assign(length_theta_, std::vector(length_phi_, 0.0)); } diff --git a/src/components/communication/ground_station_calculator.cpp b/src/components/communication/ground_station_calculator.cpp index 1322ac3a5..ced6c75cd 100644 --- a/src/components/communication/ground_station_calculator.cpp +++ b/src/components/communication/ground_station_calculator.cpp @@ -5,8 +5,8 @@ #include "ground_station_calculator.hpp" -#include #include +#include GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, const double EbN0, const double hardware_deterioration, const double coding_gain, const double margin_req, diff --git a/src/components/mission/telescope.cpp b/src/components/mission/telescope.cpp index df0d2d706..d6173563d 100644 --- a/src/components/mission/telescope.cpp +++ b/src/components/mission/telescope.cpp @@ -5,8 +5,8 @@ #include "telescope.hpp" -#include #include +#include using namespace std; using namespace libra; diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 940ff10a6..622bff9ce 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -6,13 +6,13 @@ #ifndef S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ #define S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ -#include -#include #include #include #include #include #include +#include +#include #include /* diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index 0aaa647e0..438eb64fa 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -6,10 +6,10 @@ #ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ #define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ -#include #include #include #include +#include #include "../base_classes/component_base.hpp" diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/propulsion/simple_thruster.cpp index b3846e877..5e8727aa2 100644 --- a/src/components/propulsion/simple_thruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -4,10 +4,9 @@ */ #include "simple_thruster.hpp" -#include - -#include #include +#include +#include // Constructor SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, const int id, const Vector<3> thruster_pos_b, diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 0b23787be..06145db0f 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -6,11 +6,11 @@ #ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ #define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ +#include +#include #include #include #include -#include -#include #include #include "../base_classes/component_base.hpp" diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 5d0504599..ae46586fe 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -5,10 +5,10 @@ #include "air_drag.hpp" -#include #include #include #include +#include #include "../interface/log_output/log_utility.hpp" diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index ad4c394d3..572d59e30 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -9,10 +9,10 @@ #include #include -#include "../library/math/quaternion.hpp" -#include "../library/math/vector.hpp" #include "../environment/local/atmosphere.hpp" #include "../interface/log_output/loggable.hpp" +#include "../library/math/quaternion.hpp" +#include "../library/math/vector.hpp" #include "surface_force.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index f1801626e..f934350df 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,10 +8,10 @@ #include -#include "../library/math/matrix_vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "../library/math/matrix.hpp" +#include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" -#include "../interface/log_output/loggable.hpp" #include "acceleration_disturbance.hpp" using libra::Matrix; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 264c82ddc..2bfacddd5 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,10 +8,10 @@ #include -#include "../library/math/matrix_vector.hpp" +#include "../interface/log_output/loggable.hpp" #include "../library/math/matrix.hpp" +#include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" -#include "../interface/log_output/loggable.hpp" #include "simple_disturbance.hpp" using libra::Matrix; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index bfd602f76..f88998d7a 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,9 +9,9 @@ using libra::NormalRand; #include +#include "../interface/log_output/log_utility.hpp" #include "../library/math/global_randomization.hpp" #include "../library/math/random_walk.hpp" -#include "../interface/log_output/log_utility.hpp" using namespace std; diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index e415752f1..aa7a8d9dd 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,8 +9,8 @@ #include #include -#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" +#include "../library/math/vector.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index ef067fc40..58ce78129 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,8 +10,8 @@ #include #include -#include "../library/math/vector.hpp" #include "../interface/log_output/loggable.hpp" +#include "../library/math/vector.hpp" #include "acceleration_disturbance.hpp" /** diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 3b2295203..6ab64bd06 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,9 +6,9 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ +#include #include #include -#include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 5dfa6da43..7ee95e785 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,8 +4,8 @@ */ #include "attitude_rk4.hpp" -#include #include +#include using namespace std; #include diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 053648d05..1b49a5f3d 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,9 +4,9 @@ */ #include "controlled_attitude.hpp" +#include #include #include -#include using namespace std; diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 81807883b..220e86f6d 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ #define S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ -#include "../../library/orbit/kepler_orbit.hpp" #include "../../library/math/ordinary_differential_equation.hpp" +#include "../../library/orbit/kepler_orbit.hpp" #include "orbit.hpp" /** diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 06f6b5e51..45b187fc9 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -7,8 +7,8 @@ #define S2E_DYNAMICS_ORBIT_ORBIT_HPP_ #include -#include #include +#include #include #include @@ -16,10 +16,10 @@ using libra::Matrix; using libra::Quaternion; using libra::Vector; -#include #include #include #include +#include /** * @enum OrbitPropagateMode diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 106402df9..489de2b0a 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -4,8 +4,8 @@ */ #include "rk4_orbit_propagation.hpp" -#include #include +#include #include using std::string; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index b833cc102..c973da654 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ #define S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ -#include #include +#include #include "orbit.hpp" diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index a4ff1bba4..10d20f9e9 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -5,8 +5,8 @@ #include "sgp4_orbit_propagation.hpp" -#include #include +#include #include using namespace std; diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index 6370cae82..7108a0429 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -5,9 +5,9 @@ #include "temperature.hpp" -#include #include #include +#include #include using namespace std; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index cdee27e46..299dda45c 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -10,12 +10,12 @@ #include #include -#include "library/math/matrix_vector.hpp" +#include "celestial_rotation.hpp" +#include "interface/log_output/loggable.hpp" #include "library/math/matrix.hpp" +#include "library/math/matrix_vector.hpp" #include "library/math/quaternion.hpp" #include "library/math/vector.hpp" -#include "celestial_rotation.hpp" -#include "interface/log_output/loggable.hpp" using libra::Quaternion; using libra::Vector; diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 5a744b5b3..a0e3adbe2 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -12,8 +12,8 @@ #include // for jday() #include // for gstime() -#include #include +#include #include using namespace std; diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 757f8a8fb..8217fa5a3 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,12 +10,12 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ -#include +#include +#include #include +#include #include #include -#include -#include #include using libra::Quaternion; diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 895c0c9f8..c23b4de10 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -8,12 +8,12 @@ #include //for jday() #include //for gstime() -#include -#include #include #include #include #include +#include +#include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index d380a66a6..b30a78ba0 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -6,12 +6,12 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_HPP_ #define S2E_ENVIRONMENT_GLOBAL_GNSS_SATELLITES_HPP_ -#include #include #include #include #include #include +#include #include #include diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index f375bcc74..b0f444d8e 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -4,10 +4,10 @@ */ #include "hipparcos_catalogue.hpp" -#include #include #include #include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 7c15d3a10..ec0bb8807 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,9 +6,9 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ +#include #include #include -#include #include /** diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 71fc2326c..fc553bbb3 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,12 +5,11 @@ #include "atmosphere.hpp" +#include #include - #include #include #include -#include using libra::NormalRand; using libra::Vector; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 8521305bb..519e28a47 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,11 +7,10 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ -#include - +#include #include #include -#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 9d3d0908a..064b8e57a 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -6,11 +6,11 @@ #include "geomagnetic_field.hpp" #include -#include +#include +#include #include #include -#include using libra::NormalRand; using namespace std; diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 3fc74708b..c8a3ca836 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -4,13 +4,13 @@ */ #include "solar_radiation_pressure_environment.hpp" -#include -#include #include #include #include #include #include +#include +#include using libra::Vector; using namespace std; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index f6005fdb3..732590e1d 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,9 +6,9 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ -#include #include #include +#include using libra::Vector; diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index 07676f3a3..734322df6 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -15,9 +15,9 @@ #else #include #endif +#include #include #include -#include #include #include #include diff --git a/src/interface/log_output/log_utility.hpp b/src/interface/log_output/log_utility.hpp index 3487e92fa..c15c3a9c0 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/interface/log_output/log_utility.hpp @@ -6,9 +6,9 @@ #ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ #define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ +#include #include #include -#include #include #include using libra::Matrix; diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 052b086e3..8ae62a9c9 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -6,9 +6,9 @@ #include // TODO: do not to use the functions in SGP4 library +#include #include #include -#include GeodeticPosition::GeodeticPosition() { latitude_rad_ = 0.0; diff --git a/src/library/math/matrix_vector.hpp b/src/library/math/matrix_vector.hpp index ae03f235f..82634c07c 100644 --- a/src/library/math/matrix_vector.hpp +++ b/src/library/math/matrix_vector.hpp @@ -6,8 +6,8 @@ #ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_ #define S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_P -#include "vector.hpp" #include "matrix.hpp" +#include "vector.hpp" namespace libra { diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 8fceae5d8..bb3b6684d 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -6,8 +6,8 @@ #ifndef S2E_LIBRARY_MATH_QUATERNION_HPP_ #define S2E_LIBRARY_MATH_QUATERNION_HPP_ -#include "vector.hpp" #include "matrix.hpp" +#include "vector.hpp" namespace libra { diff --git a/src/library/math/random_walk.hpp b/src/library/math/random_walk.hpp index 93fed2800..a53f24ccb 100644 --- a/src/library/math/random_walk.hpp +++ b/src/library/math/random_walk.hpp @@ -6,9 +6,9 @@ #ifndef S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ #define S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ -#include "./vector.hpp" #include "./normal_randomization.hpp" #include "./ordinary_differential_equation.hpp" +#include "./vector.hpp" /** * @class RandomWalk diff --git a/src/library/nrlmsise00/wrapper_nrlmsise00.cpp b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp index b2c07f11f..59bb7c0a6 100644 --- a/src/library/nrlmsise00/wrapper_nrlmsise00.cpp +++ b/src/library/nrlmsise00/wrapper_nrlmsise00.cpp @@ -12,11 +12,11 @@ extern "C" { } #include /* for malloc/free */ -#include #include #include #include /* maths functions */ #include +#include #include #include "wrapper_nrlmsise00.hpp" /* header for nrlmsise-00.h */ diff --git a/src/library/optics/gaussian_beam_base.cpp b/src/library/optics/gaussian_beam_base.cpp index 04500f54b..e54115ebc 100644 --- a/src/library/optics/gaussian_beam_base.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -5,8 +5,8 @@ #include "gaussian_beam_base.hpp" -#include #include +#include GaussianBeamBase::GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt) : wavelength_m_(wavelength_m), r_beam_waist_m_(r_beam_waist_m), total_power_watt_(total_power_watt) {} diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 25c441905..e1065ca67 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -5,12 +5,12 @@ #include "ground_station.hpp" -#include -#include #include #include #include #include +#include +#include #include GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id) { diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 6ad8bb569..8d5fca4f5 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ #define S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ +#include #include #include -#include #include #include "../simulation_configuration.hpp" diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 8e8fb8848..fabf51551 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_HPP_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_PARAMETERS_HPP_ +#include #include #include -#include #include #include #include diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index a1c39b8af..ef3d3b11f 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -6,9 +6,9 @@ #ifndef S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ #define S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ +#include #include #include -#include #include #include #include diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index eb1309291..aaa24e8ce 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ -#include #include +#include /** * @class InstalledComponents diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index b3afa58ed..c7e3969fc 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,7 +6,6 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ -#include #include #include #include @@ -26,6 +25,7 @@ #include #include #include +#include #include #include "../installed_components.hpp" diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index fbdd5af09..104a96200 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -5,8 +5,8 @@ #include "sample_spacecraft.hpp" -#include #include +#include #include "sample_components.hpp" diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 40a06c558..d7a103290 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,8 +5,8 @@ #include "initialize_structure.hpp" -#include #include +#include #define MIN_VAL 1e-6 KinematicsParams InitKinematicsParams(std::string ini_path) { From 32a53994075700e6999fa385bb2961db5d0c981b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 16:59:30 +0100 Subject: [PATCH 0367/1086] Fix format for external libraries --- src/library/inih/ini.c | 332 +++++++++++++++------------------- src/library/sgp4/sgp4ext.cpp | 22 +-- src/library/sgp4/sgp4unit.cpp | 22 +-- 3 files changed, 172 insertions(+), 204 deletions(-) diff --git a/src/library/inih/ini.c b/src/library/inih/ini.c index 39dbe4c32..f323a178a 100644 --- a/src/library/inih/ini.c +++ b/src/library/inih/ini.c @@ -15,12 +15,12 @@ home page for more info: #define _CRT_SECURE_NO_WARNINGS #endif -#include +#include "ini.h" + #include +#include #include -#include "ini.h" - #if !INI_USE_STACK #include #endif @@ -28,91 +28,81 @@ home page for more info: #define MAX_SECTION 50 #define MAX_NAME 50 -//#define isspace(c) (c==0x20 || c==0x0d || c==0x0a || c== 0x09 || c==0x0b || c== 0x0c) +// #define isspace(c) (c==0x20 || c==0x0d || c==0x0a || c== 0x09 || c==0x0b || c== 0x0c) /* Used by ini_parse_string() to keep track of string parsing state. */ typedef struct { - const char* ptr; - size_t num_left; + const char* ptr; + size_t num_left; } ini_parse_string_ctx; - /* Strip whitespace chars off end of given string, in place. Return s. */ -static char* rstrip(char* s) -{ - char* p = s + strlen(s); - while (p > s && isspace((unsigned char)(*--p))) - *p = '\0'; - return s; +static char* rstrip(char* s) { + char* p = s + strlen(s); + while (p > s && isspace((unsigned char)(*--p))) *p = '\0'; + return s; } /* Return pointer to first non-whitespace char in given string. */ -static char* lskip(const char* s) -{ - while (*s && isspace((unsigned char)(*s))) - s++; - return (char*)s; +static char* lskip(const char* s) { + while (*s && isspace((unsigned char)(*s))) s++; + return (char*)s; } /* Return pointer to first char (of chars) or inline comment in given string, or pointer to null at end of string if neither found. Inline comment must be prefixed by a whitespace character to register as a comment. */ -static char* find_chars_or_comment(const char* s, const char* chars) -{ +static char* find_chars_or_comment(const char* s, const char* chars) { #if INI_ALLOW_INLINE_COMMENTS - int was_space = 0; - while (*s && (!chars || !strchr(chars, *s)) && - !(was_space && strchr(INI_INLINE_COMMENT_PREFIXES, *s))) { - was_space = isspace((unsigned char)(*s)); - s++; - } + int was_space = 0; + while (*s && (!chars || !strchr(chars, *s)) && !(was_space && strchr(INI_INLINE_COMMENT_PREFIXES, *s))) { + was_space = isspace((unsigned char)(*s)); + s++; + } #else - while (*s && (!chars || !strchr(chars, *s))) { - s++; - } + while (*s && (!chars || !strchr(chars, *s))) { + s++; + } #endif - return (char*)s; + return (char*)s; } /* Version of strncpy that ensures dest (size bytes) is null-terminated. */ -static char* strncpy0(char* dest, const char* src, size_t size) -{ - strncpy(dest, src, size - 1); - dest[size - 1] = '\0'; - return dest; +static char* strncpy0(char* dest, const char* src, size_t size) { + strncpy(dest, src, size - 1); + dest[size - 1] = '\0'; + return dest; } /* See documentation in header file. */ -int ini_parse_stream(ini_reader reader, void* stream, ini_handler handler, - void* user) -{ - /* Uses a fair bit of stack (use heap instead if you need to) */ +int ini_parse_stream(ini_reader reader, void* stream, ini_handler handler, void* user) { + /* Uses a fair bit of stack (use heap instead if you need to) */ #if INI_USE_STACK - char line[INI_MAX_LINE]; - int max_line = INI_MAX_LINE; + char line[INI_MAX_LINE]; + int max_line = INI_MAX_LINE; #else - char* line; - size_t max_line = INI_INITIAL_ALLOC; + char* line; + size_t max_line = INI_INITIAL_ALLOC; #endif #if INI_ALLOW_REALLOC && !INI_USE_STACK - char* new_line; - size_t offset; + char* new_line; + size_t offset; #endif - char section[MAX_SECTION] = ""; - char prev_name[MAX_NAME] = ""; + char section[MAX_SECTION] = ""; + char prev_name[MAX_NAME] = ""; - char* start; - char* end; - char* name; - char* value; - int lineno = 0; - int error = 0; + char* start; + char* end; + char* name; + char* value; + int lineno = 0; + int error = 0; #if !INI_USE_STACK - line = (char*)malloc(INI_INITIAL_ALLOC); - if (!line) { - return -2; - } + line = (char*)malloc(INI_INITIAL_ALLOC); + if (!line) { + return -2; + } #endif #if INI_HANDLER_LINENO @@ -121,167 +111,145 @@ int ini_parse_stream(ini_reader reader, void* stream, ini_handler handler, #define HANDLER(u, s, n, v) handler(u, s, n, v) #endif - /* Scan through stream line by line */ - while (reader(line, (int)max_line, stream) != NULL) { + /* Scan through stream line by line */ + while (reader(line, (int)max_line, stream) != NULL) { #if INI_ALLOW_REALLOC && !INI_USE_STACK - offset = strlen(line); - while (offset == max_line - 1 && line[offset - 1] != '\n') { - max_line *= 2; - if (max_line > INI_MAX_LINE) - max_line = INI_MAX_LINE; - new_line = realloc(line, max_line); - if (!new_line) { - free(line); - return -2; - } - line = new_line; - if (reader(line + offset, (int)(max_line - offset), stream) == NULL) - break; - if (max_line >= INI_MAX_LINE) - break; - offset += strlen(line + offset); - } + offset = strlen(line); + while (offset == max_line - 1 && line[offset - 1] != '\n') { + max_line *= 2; + if (max_line > INI_MAX_LINE) max_line = INI_MAX_LINE; + new_line = realloc(line, max_line); + if (!new_line) { + free(line); + return -2; + } + line = new_line; + if (reader(line + offset, (int)(max_line - offset), stream) == NULL) break; + if (max_line >= INI_MAX_LINE) break; + offset += strlen(line + offset); + } #endif - lineno++; + lineno++; - start = line; + start = line; #if INI_ALLOW_BOM - if (lineno == 1 && (unsigned char)start[0] == 0xEF && - (unsigned char)start[1] == 0xBB && - (unsigned char)start[2] == 0xBF) { - start += 3; - } + if (lineno == 1 && (unsigned char)start[0] == 0xEF && (unsigned char)start[1] == 0xBB && (unsigned char)start[2] == 0xBF) { + start += 3; + } #endif - start = lskip(rstrip(start)); + start = lskip(rstrip(start)); - if (strchr(INI_START_COMMENT_PREFIXES, *start)) { - /* Start-of-line comment */ - } + if (strchr(INI_START_COMMENT_PREFIXES, *start)) { + /* Start-of-line comment */ + } #if INI_ALLOW_MULTILINE - else if (*prev_name && *start && start > line) { - /* Non-blank line with leading whitespace, treat as continuation - of previous name's value (as per Python configparser). */ - if (!HANDLER(user, section, prev_name, start) && !error) - error = lineno; - } + else if (*prev_name && *start && start > line) { + /* Non-blank line with leading whitespace, treat as continuation + of previous name's value (as per Python configparser). */ + if (!HANDLER(user, section, prev_name, start) && !error) error = lineno; + } #endif - else if (*start == '[') { - /* A "[section]" line */ - end = find_chars_or_comment(start + 1, "]"); - if (*end == ']') { - *end = '\0'; - strncpy0(section, start + 1, sizeof(section)); - *prev_name = '\0'; + else if (*start == '[') { + /* A "[section]" line */ + end = find_chars_or_comment(start + 1, "]"); + if (*end == ']') { + *end = '\0'; + strncpy0(section, start + 1, sizeof(section)); + *prev_name = '\0'; #if INI_CALL_HANDLER_ON_NEW_SECTION - if (!HANDLER(user, section, NULL, NULL) && !error) - error = lineno; + if (!HANDLER(user, section, NULL, NULL) && !error) error = lineno; #endif - } - else if (!error) { - /* No ']' found on section line */ - error = lineno; - } - } - else if (*start) { - /* Not a comment, must be a name[=:]value pair */ - end = find_chars_or_comment(start, "=:"); - if (*end == '=' || *end == ':') { - *end = '\0'; - name = rstrip(start); - value = end + 1; + } else if (!error) { + /* No ']' found on section line */ + error = lineno; + } + } else if (*start) { + /* Not a comment, must be a name[=:]value pair */ + end = find_chars_or_comment(start, "=:"); + if (*end == '=' || *end == ':') { + *end = '\0'; + name = rstrip(start); + value = end + 1; #if INI_ALLOW_INLINE_COMMENTS - end = find_chars_or_comment(value, NULL); - if (*end) - *end = '\0'; + end = find_chars_or_comment(value, NULL); + if (*end) *end = '\0'; #endif - value = lskip(value); - rstrip(value); - - /* Valid name[=:]value pair found, call handler */ - strncpy0(prev_name, name, sizeof(prev_name)); - if (!HANDLER(user, section, name, value) && !error) - error = lineno; - } - else if (!error) { - /* No '=' or ':' found on name[=:]value line */ + value = lskip(value); + rstrip(value); + + /* Valid name[=:]value pair found, call handler */ + strncpy0(prev_name, name, sizeof(prev_name)); + if (!HANDLER(user, section, name, value) && !error) error = lineno; + } else if (!error) { + /* No '=' or ':' found on name[=:]value line */ #if INI_ALLOW_NO_VALUE - *end = '\0'; - name = rstrip(start); - if (!HANDLER(user, section, name, NULL) && !error) - error = lineno; + *end = '\0'; + name = rstrip(start); + if (!HANDLER(user, section, name, NULL) && !error) error = lineno; #else - error = lineno; + error = lineno; #endif - } - } + } + } #if INI_STOP_ON_FIRST_ERROR - if (error) - break; + if (error) break; #endif - } + } #if !INI_USE_STACK - free(line); + free(line); #endif - return error; + return error; } /* See documentation in header file. */ -int ini_parse_file(FILE* file, ini_handler handler, void* user) -{ - return ini_parse_stream((ini_reader)fgets, file, handler, user); -} +int ini_parse_file(FILE* file, ini_handler handler, void* user) { return ini_parse_stream((ini_reader)fgets, file, handler, user); } /* See documentation in header file. */ -int ini_parse(const char* filename, ini_handler handler, void* user) -{ - FILE* file; - int error; - - file = fopen(filename, "r"); - if (!file) - return -1; - error = ini_parse_file(file, handler, user); - fclose(file); - return error; +int ini_parse(const char* filename, ini_handler handler, void* user) { + FILE* file; + int error; + + file = fopen(filename, "r"); + if (!file) return -1; + error = ini_parse_file(file, handler, user); + fclose(file); + return error; } /* An ini_reader function to read the next line from a string buffer. This is the fgets() equivalent used by ini_parse_string(). */ static char* ini_reader_string(char* str, int num, void* stream) { - ini_parse_string_ctx* ctx = (ini_parse_string_ctx*)stream; - const char* ctx_ptr = ctx->ptr; - size_t ctx_num_left = ctx->num_left; - char* strp = str; - char c; - - if (ctx_num_left == 0 || num < 2) - return NULL; - - while (num > 1 && ctx_num_left != 0) { - c = *ctx_ptr++; - ctx_num_left--; - *strp++ = c; - if (c == '\n') - break; - num--; - } - - *strp = '\0'; - ctx->ptr = ctx_ptr; - ctx->num_left = ctx_num_left; - return str; + ini_parse_string_ctx* ctx = (ini_parse_string_ctx*)stream; + const char* ctx_ptr = ctx->ptr; + size_t ctx_num_left = ctx->num_left; + char* strp = str; + char c; + + if (ctx_num_left == 0 || num < 2) return NULL; + + while (num > 1 && ctx_num_left != 0) { + c = *ctx_ptr++; + ctx_num_left--; + *strp++ = c; + if (c == '\n') break; + num--; + } + + *strp = '\0'; + ctx->ptr = ctx_ptr; + ctx->num_left = ctx_num_left; + return str; } /* See documentation in header file. */ int ini_parse_string(const char* string, ini_handler handler, void* user) { - ini_parse_string_ctx ctx; + ini_parse_string_ctx ctx; - ctx.ptr = string; - ctx.num_left = strlen(string); - return ini_parse_stream((ini_reader)ini_reader_string, &ctx, handler, - user); + ctx.ptr = string; + ctx.num_left = strlen(string); + return ini_parse_stream((ini_reader)ini_reader_string, &ctx, handler, user); } diff --git a/src/library/sgp4/sgp4ext.cpp b/src/library/sgp4/sgp4ext.cpp index ce67f19e5..593a93c21 100644 --- a/src/library/sgp4/sgp4ext.cpp +++ b/src/library/sgp4/sgp4ext.cpp @@ -37,8 +37,8 @@ #define X3PIO2 4.71238898038468967 /* 3*Pi/2 */ #define TWOPI 6.28318530717958623 /* 2*Pi */ -//座標変換用 -//回転関数x軸周り[rad] +// 座標変換用 +// 回転関数x軸周り[rad] int RotationX(const double* bfr, double* aft, double theta) { double temp[3]; @@ -53,8 +53,8 @@ int RotationX(const double* bfr, double* aft, double theta) { return 0; } -//座標変換用 -//回転関数Y軸周り[rad] +// 座標変換用 +// 回転関数Y軸周り[rad] int RotationY(const double* bfr, double* aft, double theta) { double temp[3]; @@ -69,8 +69,8 @@ int RotationY(const double* bfr, double* aft, double theta) { return 0; } -//座標変換用 -//回転関数Z軸周り[rad] +// 座標変換用 +// 回転関数Z軸周り[rad] int RotationZ(const double* bfr, double* aft, double theta) { double temp[3]; @@ -85,7 +85,7 @@ int RotationZ(const double* bfr, double* aft, double theta) { return 0; } -//座標変換用 +// 座標変換用 double AcTan(double sinx, double cosx) { /* Four-quadrant arctan function */ @@ -109,7 +109,7 @@ double AcTan(double sinx, double cosx) { } } -//座標変換用 +// 座標変換用 double FMod2p(double x) { /* Returns mod 2PI of argument */ @@ -505,7 +505,7 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e nu = undefined; // ---- find argument of latitude - circular inclined ----- - //緯度の計算(円の/傾斜面の) + // 緯度の計算(円の/傾斜面の) if (strcmp(typeorbit, "ci") == 0) { arglat = angle(nbar, r); if (r[2] < 0.0) arglat = twopi - arglat; @@ -524,7 +524,7 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e lonper = undefined; // -------- find true longitude - circular equatorial ------ - //真の経度の計算(円の/赤道の) + // 真の経度の計算(円の/赤道の) if ((magr > small) && (strcmp(typeorbit, "ce") == 0)) { temp = r[0] / magr; if (fabs(temp) > 1.0) temp = sgn(temp); // sgn()は符号関数 @@ -729,7 +729,7 @@ void invjday(double jd, int& year, int& mon, int& day, int& hr, int& minute, dou sec = sec - 0.00000086400; } // end invjday -//ユリウス日からDecimalYear(yearの小数点表記)の計算 +// ユリウス日からDecimalYear(yearの小数点表記)の計算 void JdToDecyear(double jd, double* decyear) { int leapyrs, year; double days, tu, temp; diff --git a/src/library/sgp4/sgp4unit.cpp b/src/library/sgp4/sgp4unit.cpp index a9c7818cc..1fee6762c 100644 --- a/src/library/sgp4/sgp4unit.cpp +++ b/src/library/sgp4/sgp4unit.cpp @@ -36,8 +36,8 @@ #include "sgp4unit.h" -#include #include +#include const char help = 'n'; FILE* dbgfile; @@ -251,7 +251,7 @@ static void dpper(double e3, double ee2, double peo, double pgho, double pho, do } } // if init == 'n' - //#include "debug1.cpp" + // #include "debug1.cpp" } // end dpper /*----------------------------------------------------------------------------- @@ -498,7 +498,7 @@ static void dscom(double epoch, double ep, double argpp, double tc, double inclp xh2 = -2.0 * s2 * z22; xh3 = -2.0 * s2 * (z23 - z21); - //#include "debug2.cpp" + // #include "debug2.cpp" } // end dscom /*----------------------------------------------------------------------------- @@ -764,7 +764,7 @@ static void dsinit(gravconsttype whichconst, double cosim, double emsq, double a nm = no + dndt; } - //#include "debug3.cpp" + // #include "debug3.cpp" } // end dsinit /*----------------------------------------------------------------------------- @@ -966,7 +966,7 @@ static void dspace(int irez, double d2201, double d2211, double d3210, double d3 nm = no + dndt; } - //#include "debug4.cpp" + // #include "debug4.cpp" } // end dsspace /*----------------------------------------------------------------------------- @@ -1083,7 +1083,7 @@ static void initl(int satn, gravconsttype whichconst, double ecco, double epoch, gsto = fmod(thgr70 + c1 * ids70 + c1p2p * tfrac + ts70 * ts70 * fk5r, twopi); if (gsto < 0.0) gsto = gsto + twopi; - //#include "debug5.cpp" + // #include "debug5.cpp" } // end initl /*----------------------------------------------------------------------------- @@ -1406,7 +1406,7 @@ int sgp4init(gravconsttype whichconst, const int satn, const double epoch, const satrec.init = 'n'; - //#include "debug6.cpp" + // #include "debug6.cpp" return satrec.error; } // end sgp4init @@ -1523,7 +1523,7 @@ int sgp4(gravconsttype whichconst, elsetrec& satrec, double tsince, double r[3], satrec.error = 0; /* ------- update for secular gravity and atmospheric drag ----- */ - //永続的な重力と大気抵抗のアップデート + // 永続的な重力と大気抵抗のアップデート xmdf = satrec.mo + satrec.mdot * satrec.t; argpdf = satrec.argpo + satrec.argpdot * satrec.t; nodedf = satrec.nodeo + satrec.nodedot * satrec.t; @@ -1628,7 +1628,7 @@ int sgp4(gravconsttype whichconst, elsetrec& satrec, double tsince, double r[3], xl = mp + argpp + nodep + temp * satrec.xlcof * axnl; /* --------------------- solve kepler's equation --------------- */ - //ケプラー方程式を解く + // ケプラー方程式を解く u = fmod(xl - nodep, twopi); eo1 = u; tem5 = 9999.9; @@ -1710,13 +1710,13 @@ int sgp4(gravconsttype whichconst, elsetrec& satrec, double tsince, double r[3], } // if pl > 0 // sgp4fix for decaying satellites - if (mrt < 1.0) //地球に激突して破壊? + if (mrt < 1.0) // 地球に激突して破壊? { // printf("# decay condition %11.6f \n",mrt); satrec.error = 6; } - //#include "debug7.cpp" + // #include "debug7.cpp" return satrec.error; } // end sgp4 From b68ace1f9aafe93035535a86a26441051cb3346c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 8 Feb 2023 19:03:51 +0100 Subject: [PATCH 0368/1086] Revert README --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index dbb69b235..ec8430d76 100644 --- a/README.md +++ b/README.md @@ -95,5 +95,5 @@ ## Publications -1. S. Ikari, and et al., "Development of Compact and Highly Capable Integrated aocs Module for CubeSats", [2022-f-41](https://archive.ists.ne.jp/upload_pdf/F-9-05.pdf), 33rd ISTS, 2022. +1. S. Ikari, and et al., "Development of Compact and Highly Capable Integrated AOCS Module for CubeSats", [2022-f-41](https://archive.ists.ne.jp/upload_pdf/F-9-05.pdf), 33rd ISTS, 2022. 1. 五十里, 他, "宇宙開発の効率化・高度化を目指した東京大学中須賀・船瀬研のOSS活動", [UNISEC2022-04](http://unisec.jp/archives/7836), 12th UNISEC Space Takumi Conference, 2022. From ec9af08242c92e823652ca354ea7a931a9fb27c4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:08:35 +0100 Subject: [PATCH 0369/1086] Integrate CMakeList in library --- CMakeLists.txt | 30 ++++++++------------------- src/library/geodesy/CMakeLists.txt | 8 ------- src/library/igrf/CMakeLists.txt | 9 -------- src/library/inih/CMakeLists.txt | 9 -------- src/library/math/CMakeLists.txt | 15 -------------- src/library/nrlmsise00/CMakeLists.txt | 9 -------- src/library/optics/CMakeLists.txt | 8 ------- src/library/orbit/CMakeLists.txt | 10 --------- src/library/sgp4/CMakeLists.txt | 13 ------------ src/library/utilities/CMakeLists.txt | 9 -------- 10 files changed, 9 insertions(+), 111 deletions(-) delete mode 100644 src/library/geodesy/CMakeLists.txt delete mode 100644 src/library/igrf/CMakeLists.txt delete mode 100644 src/library/inih/CMakeLists.txt delete mode 100644 src/library/math/CMakeLists.txt delete mode 100644 src/library/nrlmsise00/CMakeLists.txt delete mode 100644 src/library/optics/CMakeLists.txt delete mode 100644 src/library/orbit/CMakeLists.txt delete mode 100644 src/library/sgp4/CMakeLists.txt delete mode 100644 src/library/utilities/CMakeLists.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index fd54c6cbb..bac93ab5b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -74,15 +74,7 @@ add_subdirectory(src/interface/initialize) add_subdirectory(src/interface/log_output) add_subdirectory(src/interface/sils) add_subdirectory(src/interface/hils) -add_subdirectory(src/library/igrf) -add_subdirectory(src/library/inih) -add_subdirectory(src/library/math) -add_subdirectory(src/library/nrlmsise00) -add_subdirectory(src/library/sgp4) -add_subdirectory(src/library/utilities) -add_subdirectory(src/library/optics) -add_subdirectory(src/library/orbit) -add_subdirectory(src/library/geodesy) +add_subdirectory(src/library) set(SOURCE_FILES src/s2e.cpp @@ -150,18 +142,14 @@ if(NOT NRLMSISE00_LIB) endif() #target_link_libraries(${PROJECT_NAME} ${NRLMSISE00_LIB}) -## Linking libraries -set(S2E_LIBRARIES - IGRF WRAPPER_NRLMSISE00 INIH SGP4 UTIL OPTICS ORBIT_MODELS GEODESY MATH -) # Initialize link -target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SC_IO RELATIVE_INFO ${S2E_LIBRARIES}) -target_link_libraries(DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SIMULATION ${S2E_LIBRARIES}) -target_link_libraries(DISTURBANCE DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT ${S2E_LIBRARIES}) -target_link_libraries(SIMULATION DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT DISTURBANCE ${S2E_LIBRARIES}) -target_link_libraries(GLOBAL_ENVIRONMENT ${CSPICE_LIB} ${S2E_LIBRARIES}) -target_link_libraries(LOCAL_ENVIRONMENT GLOBAL_ENVIRONMENT ${CSPICE_LIB} ${S2E_LIBRARIES}) -target_link_libraries(WRAPPER_NRLMSISE00 ${NRLMSISE00_LIB}) +target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SC_IO RELATIVE_INFO LIBRARY) +target_link_libraries(DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SIMULATION LIBRARY) +target_link_libraries(DISTURBANCE DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT LIBRARY) +target_link_libraries(SIMULATION DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT DISTURBANCE LIBRARY) +target_link_libraries(GLOBAL_ENVIRONMENT ${CSPICE_LIB} LIBRARY) +target_link_libraries(LOCAL_ENVIRONMENT GLOBAL_ENVIRONMENT ${CSPICE_LIB} LIBRARY) +target_link_libraries(LIBRARY ${NRLMSISE00_LIB}) target_link_libraries(${PROJECT_NAME} DYNAMICS) target_link_libraries(${PROJECT_NAME} DISTURBANCE) @@ -215,7 +203,7 @@ if(GOOGLE_TEST) ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) - target_link_libraries(${TEST_PROJECT_NAME} MATH) + target_link_libraries(${TEST_PROJECT_NAME} LIBRARY) include_directories(${TEST_PROJECT_NAME}) add_test(NAME s2e-test COMMAND ${TEST_PROJECT_NAME}) enable_testing() diff --git a/src/library/geodesy/CMakeLists.txt b/src/library/geodesy/CMakeLists.txt deleted file mode 100644 index 61eb66efd..000000000 --- a/src/library/geodesy/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -project(GEODESY) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - geodetic_position.cpp -) - -include(../../../common.cmake) diff --git a/src/library/igrf/CMakeLists.txt b/src/library/igrf/CMakeLists.txt deleted file mode 100644 index 48fef2949..000000000 --- a/src/library/igrf/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(IGRF) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - igrf.cpp - igrf.h -) - -include(../../../common.cmake) diff --git a/src/library/inih/CMakeLists.txt b/src/library/inih/CMakeLists.txt deleted file mode 100644 index 96721e972..000000000 --- a/src/library/inih/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(INIH) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - ini.c - cpp/INIReader.cpp -) - -include(../../../common.cmake) diff --git a/src/library/math/CMakeLists.txt b/src/library/math/CMakeLists.txt deleted file mode 100644 index 769797d4b..000000000 --- a/src/library/math/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -project(MATH) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - global_randomization.cpp - normal_randomization.cpp - quantization.cpp - quaternion.cpp - randomize0.cpp - randomize1.cpp - vector.cpp - s2e_math.cpp -) - -include(../../../common.cmake) diff --git a/src/library/nrlmsise00/CMakeLists.txt b/src/library/nrlmsise00/CMakeLists.txt deleted file mode 100644 index f3156ecb2..000000000 --- a/src/library/nrlmsise00/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(WRAPPER_NRLMSISE00) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - wrapper_nrlmsise00.cpp - wrapper_nrlmsise00.hpp -) - -include(../../../common.cmake) diff --git a/src/library/optics/CMakeLists.txt b/src/library/optics/CMakeLists.txt deleted file mode 100644 index 165dbed4c..000000000 --- a/src/library/optics/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -project(OPTICS) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - gaussian_beam_base.cpp -) - -include(../../../common.cmake) diff --git a/src/library/orbit/CMakeLists.txt b/src/library/orbit/CMakeLists.txt deleted file mode 100644 index f77d72d86..000000000 --- a/src/library/orbit/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -project(ORBIT_MODELS) -cmake_minimum_required(VERSION 3.10) - -add_library(${PROJECT_NAME} STATIC - orbital_elements.cpp - kepler_orbit.cpp - relative_orbit_models.cpp -) - -include(../../../common.cmake) diff --git a/src/library/sgp4/CMakeLists.txt b/src/library/sgp4/CMakeLists.txt deleted file mode 100644 index 2218a6258..000000000 --- a/src/library/sgp4/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -project(SGP4) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - sgp4ext.cpp - sgp4ext.h - sgp4io.cpp - sgp4io.h - sgp4unit.cpp - sgp4unit.h -) - -include(../../../common.cmake) diff --git a/src/library/utilities/CMakeLists.txt b/src/library/utilities/CMakeLists.txt deleted file mode 100644 index df603d74c..000000000 --- a/src/library/utilities/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(UTIL) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - endian.cpp - slip.cpp -) - -include(../../../common.cmake) From fdea4174048b85244d99d33887f1dab6a4d00a85 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:08:50 +0100 Subject: [PATCH 0370/1086] Integrate CMakeList in library --- src/library/CMakeLists.txt | 37 +++++++++++++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100644 src/library/CMakeLists.txt diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt new file mode 100644 index 000000000..b98ff8c76 --- /dev/null +++ b/src/library/CMakeLists.txt @@ -0,0 +1,37 @@ +project(LIBRARY) +cmake_minimum_required(VERSION 3.13) + +add_library(${PROJECT_NAME} STATIC + geodesy/geodetic_position.cpp + + igrf/igrf.cpp + + inih/ini.c + inih/cpp/INIReader.cpp + + math/global_randomization.cpp + math/normal_randomization.cpp + math/quantization.cpp + math/quaternion.cpp + math/randomize0.cpp + math/randomize1.cpp + math/vector.cpp + math/s2e_math.cpp + + nrlmsise00/wrapper_nrlmsise00.cpp + + optics/gaussian_beam_base.cpp + + orbit/orbital_elements.cpp + orbit/kepler_orbit.cpp + orbit/relative_orbit_models.cpp + + sgp4/sgp4ext.cpp + sgp4/sgp4io.cpp + sgp4/sgp4unit.cpp + + utilities/endian.cpp + utilities/slip.cpp +) + +include(../../common.cmake) From 7d10725f3c8ecb5a64eb3a58a0b8e64cf6d7ddc8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:10:50 +0100 Subject: [PATCH 0371/1086] Add CMake for interface --- src/interface/CMakeLists.txt | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 src/interface/CMakeLists.txt diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt new file mode 100644 index 000000000..2f13d655c --- /dev/null +++ b/src/interface/CMakeLists.txt @@ -0,0 +1,8 @@ +project(INTERFACE) +cmake_minimum_required(VERSION 3.13) + +add_library(${PROJECT_NAME} STATIC + +) + +include(../../common.cmake) From f1718f580984913578765769b4f3241876b5cf34 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:13:35 +0100 Subject: [PATCH 0372/1086] Delete Cmake for hils --- src/interface/CMakeLists.txt | 14 +++++++++++--- src/interface/hils/CMakeLists.txt | 16 ---------------- 2 files changed, 11 insertions(+), 19 deletions(-) delete mode 100644 src/interface/hils/CMakeLists.txt diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 2f13d655c..352e63457 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -1,8 +1,16 @@ project(INTERFACE) cmake_minimum_required(VERSION 3.13) -add_library(${PROJECT_NAME} STATIC - -) +if(USE_HILS) + add_library(${PROJECT_NAME} STATIC + hils/hils_port_manager.cpp + hils/ports/hils_uart_port.cpp + hils/ports/hils_i2c_target_port.cpp + ) +else() + add_library(${PROJECT_NAME} STATIC + hils/hils_port_manager.cpp + ) +endif() include(../../common.cmake) diff --git a/src/interface/hils/CMakeLists.txt b/src/interface/hils/CMakeLists.txt deleted file mode 100644 index 66e6ff4e9..000000000 --- a/src/interface/hils/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -project(HILS_IO) -cmake_minimum_required(VERSION 3.13) - -if(USE_HILS) -add_library(${PROJECT_NAME} STATIC - hils_port_manager.cpp - ports/hils_uart_port.cpp - ports/hils_i2c_target_port.cpp - ) -else() -add_library(${PROJECT_NAME} STATIC - hils_port_manager.cpp - ) -endif() - -include(../../../common.cmake) From b4cce648aabbf2dad5b3fbf4b2b4d8001de845ca Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:14:17 +0100 Subject: [PATCH 0373/1086] Delete Cmake for initialize --- src/interface/CMakeLists.txt | 4 ++++ src/interface/initialize/CMakeLists.txt | 8 -------- 2 files changed, 4 insertions(+), 8 deletions(-) delete mode 100644 src/interface/initialize/CMakeLists.txt diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 352e63457..bd04ad907 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -3,12 +3,16 @@ cmake_minimum_required(VERSION 3.13) if(USE_HILS) add_library(${PROJECT_NAME} STATIC + initialize_file_access.cpp + hils/hils_port_manager.cpp hils/ports/hils_uart_port.cpp hils/ports/hils_i2c_target_port.cpp ) else() add_library(${PROJECT_NAME} STATIC + initialize_file_access.cpp + hils/hils_port_manager.cpp ) endif() diff --git a/src/interface/initialize/CMakeLists.txt b/src/interface/initialize/CMakeLists.txt deleted file mode 100644 index 4299474c8..000000000 --- a/src/interface/initialize/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -project(INI_ACC) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - initialize_file_access.cpp -) - -include(../../../common.cmake) From fda819b58a9112a0b2407b34cf094a48bb5f22e5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:15:15 +0100 Subject: [PATCH 0374/1086] Delete Cmake for log_output --- src/interface/CMakeLists.txt | 5 ++++- src/interface/log_output/CMakeLists.txt | 9 --------- 2 files changed, 4 insertions(+), 10 deletions(-) delete mode 100644 src/interface/log_output/CMakeLists.txt diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index bd04ad907..ed8140aa5 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -11,8 +11,11 @@ if(USE_HILS) ) else() add_library(${PROJECT_NAME} STATIC - initialize_file_access.cpp + initialize/initialize_file_access.cpp + log_output/logger.cpp + log_output/initialize_log.cpp + hils/hils_port_manager.cpp ) endif() diff --git a/src/interface/log_output/CMakeLists.txt b/src/interface/log_output/CMakeLists.txt deleted file mode 100644 index eb2f6d9f5..000000000 --- a/src/interface/log_output/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -project(LOG_OUT) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - logger.cpp - initialize_log.cpp -) - -include(../../../common.cmake) From c93dd105ece28cd22d2b3405fb68be1e81677c37 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:16:23 +0100 Subject: [PATCH 0375/1086] Delete Cmake for sils --- src/interface/CMakeLists.txt | 15 +++++++++++++++ src/interface/sils/CMakeLists.txt | 12 ------------ 2 files changed, 15 insertions(+), 12 deletions(-) delete mode 100644 src/interface/sils/CMakeLists.txt diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index ed8140aa5..5c3d2a2dd 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -4,6 +4,15 @@ cmake_minimum_required(VERSION 3.13) if(USE_HILS) add_library(${PROJECT_NAME} STATIC initialize_file_access.cpp + + log_output/logger.cpp + log_output/initialize_log.cpp + + sils/ports/gpio_port.cpp + sils/ports/power_port.cpp + sils/ports/uart_port.cpp + sils/ports/i2c_port.cpp + sils/utility/ring_buffer.cpp hils/hils_port_manager.cpp hils/ports/hils_uart_port.cpp @@ -16,6 +25,12 @@ else() log_output/logger.cpp log_output/initialize_log.cpp + sils/ports/gpio_port.cpp + sils/ports/power_port.cpp + sils/ports/uart_port.cpp + sils/ports/i2c_port.cpp + sils/utility/ring_buffer.cpp + hils/hils_port_manager.cpp ) endif() diff --git a/src/interface/sils/CMakeLists.txt b/src/interface/sils/CMakeLists.txt deleted file mode 100644 index 931d99abc..000000000 --- a/src/interface/sils/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -project(SC_IO) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - ports/gpio_port.cpp - ports/power_port.cpp - ports/uart_port.cpp - ports/i2c_port.cpp - utility/ring_buffer.cpp -) - -include(../../../common.cmake) From 8e9e13b4e67e5ef3351abefbfd0fc6bccc997187 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:26:53 +0100 Subject: [PATCH 0376/1086] Fix main CMakeList --- CMakeLists.txt | 13 ++++--------- src/interface/CMakeLists.txt | 4 ++-- 2 files changed, 6 insertions(+), 11 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index bac93ab5b..ad8bae148 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,10 +70,7 @@ add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/components) add_subdirectory(src/relative_information) -add_subdirectory(src/interface/initialize) -add_subdirectory(src/interface/log_output) -add_subdirectory(src/interface/sils) -add_subdirectory(src/interface/hils) +add_subdirectory(src/interface) add_subdirectory(src/library) set(SOURCE_FILES @@ -143,7 +140,7 @@ endif() #target_link_libraries(${PROJECT_NAME} ${NRLMSISE00_LIB}) # Initialize link -target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SC_IO RELATIVE_INFO LIBRARY) +target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT INTERFACE_ RELATIVE_INFO LIBRARY) target_link_libraries(DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SIMULATION LIBRARY) target_link_libraries(DISTURBANCE DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT LIBRARY) target_link_libraries(SIMULATION DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT DISTURBANCE LIBRARY) @@ -156,14 +153,12 @@ target_link_libraries(${PROJECT_NAME} DISTURBANCE) target_link_libraries(${PROJECT_NAME} SIMULATION) target_link_libraries(${PROJECT_NAME} GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT) target_link_libraries(${PROJECT_NAME} RELATIVE_INFO) -target_link_libraries(${PROJECT_NAME} INI_ACC LOG_OUT SC_IO) +target_link_libraries(${PROJECT_NAME} INTERFACE_) target_link_libraries(${PROJECT_NAME} COMPONENT) -target_link_libraries(${PROJECT_NAME} HILS_IO) ## C2A integration if(USE_C2A) target_link_libraries(${PROJECT_NAME} C2A) - target_link_libraries(${PROJECT_NAME} SC_IO) endif() ## HILS @@ -176,7 +171,7 @@ if(USE_HILS) set_target_properties(SIMULATION PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(GLOBAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(LOCAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") - set_target_properties(HILS_IO PROPERTIES COMMON_LANGUAGE_RUNTIME "") + set_target_properties(INTERFACE_ PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(RELATIVE_INFO PROPERTIES COMMON_LANGUAGE_RUNTIME "") endif() diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 5c3d2a2dd..e70cc3b02 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -1,4 +1,4 @@ -project(INTERFACE) +project(INTERFACE_) # INTERFACEだけだとCMakeの予約後に引っかかってしまうよう cmake_minimum_required(VERSION 3.13) if(USE_HILS) @@ -13,7 +13,7 @@ if(USE_HILS) sils/ports/uart_port.cpp sils/ports/i2c_port.cpp sils/utility/ring_buffer.cpp - + hils/hils_port_manager.cpp hils/ports/hils_uart_port.cpp hils/ports/hils_i2c_target_port.cpp From 7c71e9cb554ea105ee22be3b4ee38a4841f46af1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 20:49:17 +0100 Subject: [PATCH 0377/1086] Fix source file settings --- src/interface/CMakeLists.txt | 45 +++++++++++++++--------------------- 1 file changed, 19 insertions(+), 26 deletions(-) diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index e70cc3b02..cd26fcb28 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -1,38 +1,31 @@ project(INTERFACE_) # INTERFACEだけだとCMakeの予約後に引っかかってしまうよう cmake_minimum_required(VERSION 3.13) -if(USE_HILS) - add_library(${PROJECT_NAME} STATIC - initialize_file_access.cpp +set(SOURCE_FILES + initialize/initialize_file_access.cpp + + log_output/logger.cpp + log_output/initialize_log.cpp - log_output/logger.cpp - log_output/initialize_log.cpp + sils/ports/gpio_port.cpp + sils/ports/power_port.cpp + sils/ports/uart_port.cpp + sils/ports/i2c_port.cpp + sils/utility/ring_buffer.cpp - sils/ports/gpio_port.cpp - sils/ports/power_port.cpp - sils/ports/uart_port.cpp - sils/ports/i2c_port.cpp - sils/utility/ring_buffer.cpp + hils/hils_port_manager.cpp +) - hils/hils_port_manager.cpp +if(USE_HILS) + set(SOURCE_FILES + ${SOURCE_FILES} hils/ports/hils_uart_port.cpp hils/ports/hils_i2c_target_port.cpp - ) -else() - add_library(${PROJECT_NAME} STATIC - initialize/initialize_file_access.cpp - - log_output/logger.cpp - log_output/initialize_log.cpp - - sils/ports/gpio_port.cpp - sils/ports/power_port.cpp - sils/ports/uart_port.cpp - sils/ports/i2c_port.cpp - sils/utility/ring_buffer.cpp - - hils/hils_port_manager.cpp ) endif() +add_library(${PROJECT_NAME} STATIC + ${SOURCE_FILES} +) + include(../../common.cmake) From 10caec5238c2286385353d993ecd853e84a258f6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:07:41 +0100 Subject: [PATCH 0378/1086] Rename component/base_classes --- src/components/CMakeLists.txt | 10 +++++----- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/gyro_sensor.hpp | 4 ++-- src/components/aocs/initialize_gyro_sensor.cpp | 2 +- src/components/aocs/initialize_magnetometer.cpp | 2 +- src/components/aocs/magnetometer.hpp | 4 ++-- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- .../{base_classes => base}/component_base.cpp | 0 .../{base_classes => base}/component_base.hpp | 0 .../i2c_controller_communication_base.cpp | 0 .../i2c_controller_communication_base.hpp | 0 .../{base_classes => base}/initialize_sensor_base.hpp | 0 .../initialize_sensor_base_tfs.hpp | 0 .../interface_gpio_component.hpp | 0 .../{base_classes => base}/interface_tickable.hpp | 0 .../{base_classes => base}/obc_communication_base.cpp | 0 .../{base_classes => base}/obc_communication_base.hpp | 0 .../{base_classes => base}/obc_gpio_base.cpp | 0 .../{base_classes => base}/obc_gpio_base.hpp | 0 .../obc_i2c_target_communication_base.cpp | 0 .../obc_i2c_target_communication_base.hpp | 0 src/components/{base_classes => base}/sensor_base.hpp | 0 .../{base_classes => base}/sensor_base_tfs.hpp | 0 src/components/cdh/obc.hpp | 2 +- src/components/examples/example_change_structure.hpp | 2 +- .../examples/example_i2c_controller_for_hils.hpp | 4 ++-- .../examples/example_i2c_target_for_hils.hpp | 4 ++-- .../examples/example_serial_communication_for_hils.hpp | 4 ++-- .../examples/example_serial_communication_with_obc.hpp | 6 +++--- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/mission/telescope.hpp | 2 +- src/components/power/battery.hpp | 2 +- src/components/power/pcu_initial_study.hpp | 2 +- src/components/power/power_control_unit.hpp | 2 +- src/components/power/solar_array_panel.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/environment/global/clock_generator.hpp | 2 +- src/interface/hils/com_port_interface.hpp | 2 +- src/interface/sils/ports/gpio_port.hpp | 2 +- 43 files changed, 38 insertions(+), 38 deletions(-) rename src/components/{base_classes => base}/component_base.cpp (100%) rename src/components/{base_classes => base}/component_base.hpp (100%) rename src/components/{base_classes => base}/i2c_controller_communication_base.cpp (100%) rename src/components/{base_classes => base}/i2c_controller_communication_base.hpp (100%) rename src/components/{base_classes => base}/initialize_sensor_base.hpp (100%) rename src/components/{base_classes => base}/initialize_sensor_base_tfs.hpp (100%) rename src/components/{base_classes => base}/interface_gpio_component.hpp (100%) rename src/components/{base_classes => base}/interface_tickable.hpp (100%) rename src/components/{base_classes => base}/obc_communication_base.cpp (100%) rename src/components/{base_classes => base}/obc_communication_base.hpp (100%) rename src/components/{base_classes => base}/obc_gpio_base.cpp (100%) rename src/components/{base_classes => base}/obc_gpio_base.hpp (100%) rename src/components/{base_classes => base}/obc_i2c_target_communication_base.cpp (100%) rename src/components/{base_classes => base}/obc_i2c_target_communication_base.hpp (100%) rename src/components/{base_classes => base}/sensor_base.hpp (100%) rename src/components/{base_classes => base}/sensor_base_tfs.hpp (100%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index ecf19b4f0..798d9e5e7 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -2,11 +2,11 @@ project(COMPONENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - base_classes/component_base.cpp - base_classes/obc_communication_base.cpp - base_classes/i2c_controller_communication_base.cpp - base_classes/obc_i2c_target_communication_base.cpp - base_classes/obc_gpio_base.cpp + base/component_base.cpp + base/obc_communication_base.cpp + base/i2c_controller_communication_base.cpp + base/obc_i2c_target_communication_base.cpp + base/obc_gpio_base.cpp aocs/gyro_sensor.cpp aocs/initialize_gyro_sensor.cpp diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index bd8913bec..a1c848636 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" using libra::Vector; diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index e24dbf7a2..823634c7e 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -10,8 +10,8 @@ #include #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/sensor_base.hpp" +#include "../base/component_base.hpp" +#include "../base/sensor_base.hpp" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/aocs/initialize_gyro_sensor.cpp b/src/components/aocs/initialize_gyro_sensor.cpp index 08a686efe..a2bd8fafd 100644 --- a/src/components/aocs/initialize_gyro_sensor.cpp +++ b/src/components/aocs/initialize_gyro_sensor.cpp @@ -6,7 +6,7 @@ #include -#include "../base_classes/initialize_sensor_base.hpp" +#include "../base/initialize_sensor_base.hpp" Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); diff --git a/src/components/aocs/initialize_magnetometer.cpp b/src/components/aocs/initialize_magnetometer.cpp index 3c7658af7..f0efd5647 100644 --- a/src/components/aocs/initialize_magnetometer.cpp +++ b/src/components/aocs/initialize_magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "initialize_magnetometer.hpp" -#include "../base_classes/initialize_sensor_base.hpp" +#include "../base/initialize_sensor_base.hpp" #include "interface/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 5e62223b0..5cdd1d1ee 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -10,8 +10,8 @@ #include #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/sensor_base.hpp" +#include "../base/component_base.hpp" +#include "../base/sensor_base.hpp" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 2fcb2a31a..3b0700908 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -14,7 +14,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" const size_t kMtqDim = 3; //!< Dimension of magnetorquer diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index 847405548..ff0969170 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" #include "reaction_wheel_jitter.hpp" #include "reaction_wheel_ode.hpp" diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index ba883516e..2531fa9fb 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -15,7 +15,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" #include "dynamics/dynamics.hpp" /* diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 7714fabf8..151b6cc54 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /* * @class SunSensor diff --git a/src/components/base_classes/component_base.cpp b/src/components/base/component_base.cpp similarity index 100% rename from src/components/base_classes/component_base.cpp rename to src/components/base/component_base.cpp diff --git a/src/components/base_classes/component_base.hpp b/src/components/base/component_base.hpp similarity index 100% rename from src/components/base_classes/component_base.hpp rename to src/components/base/component_base.hpp diff --git a/src/components/base_classes/i2c_controller_communication_base.cpp b/src/components/base/i2c_controller_communication_base.cpp similarity index 100% rename from src/components/base_classes/i2c_controller_communication_base.cpp rename to src/components/base/i2c_controller_communication_base.cpp diff --git a/src/components/base_classes/i2c_controller_communication_base.hpp b/src/components/base/i2c_controller_communication_base.hpp similarity index 100% rename from src/components/base_classes/i2c_controller_communication_base.hpp rename to src/components/base/i2c_controller_communication_base.hpp diff --git a/src/components/base_classes/initialize_sensor_base.hpp b/src/components/base/initialize_sensor_base.hpp similarity index 100% rename from src/components/base_classes/initialize_sensor_base.hpp rename to src/components/base/initialize_sensor_base.hpp diff --git a/src/components/base_classes/initialize_sensor_base_tfs.hpp b/src/components/base/initialize_sensor_base_tfs.hpp similarity index 100% rename from src/components/base_classes/initialize_sensor_base_tfs.hpp rename to src/components/base/initialize_sensor_base_tfs.hpp diff --git a/src/components/base_classes/interface_gpio_component.hpp b/src/components/base/interface_gpio_component.hpp similarity index 100% rename from src/components/base_classes/interface_gpio_component.hpp rename to src/components/base/interface_gpio_component.hpp diff --git a/src/components/base_classes/interface_tickable.hpp b/src/components/base/interface_tickable.hpp similarity index 100% rename from src/components/base_classes/interface_tickable.hpp rename to src/components/base/interface_tickable.hpp diff --git a/src/components/base_classes/obc_communication_base.cpp b/src/components/base/obc_communication_base.cpp similarity index 100% rename from src/components/base_classes/obc_communication_base.cpp rename to src/components/base/obc_communication_base.cpp diff --git a/src/components/base_classes/obc_communication_base.hpp b/src/components/base/obc_communication_base.hpp similarity index 100% rename from src/components/base_classes/obc_communication_base.hpp rename to src/components/base/obc_communication_base.hpp diff --git a/src/components/base_classes/obc_gpio_base.cpp b/src/components/base/obc_gpio_base.cpp similarity index 100% rename from src/components/base_classes/obc_gpio_base.cpp rename to src/components/base/obc_gpio_base.cpp diff --git a/src/components/base_classes/obc_gpio_base.hpp b/src/components/base/obc_gpio_base.hpp similarity index 100% rename from src/components/base_classes/obc_gpio_base.hpp rename to src/components/base/obc_gpio_base.hpp diff --git a/src/components/base_classes/obc_i2c_target_communication_base.cpp b/src/components/base/obc_i2c_target_communication_base.cpp similarity index 100% rename from src/components/base_classes/obc_i2c_target_communication_base.cpp rename to src/components/base/obc_i2c_target_communication_base.cpp diff --git a/src/components/base_classes/obc_i2c_target_communication_base.hpp b/src/components/base/obc_i2c_target_communication_base.hpp similarity index 100% rename from src/components/base_classes/obc_i2c_target_communication_base.hpp rename to src/components/base/obc_i2c_target_communication_base.hpp diff --git a/src/components/base_classes/sensor_base.hpp b/src/components/base/sensor_base.hpp similarity index 100% rename from src/components/base_classes/sensor_base.hpp rename to src/components/base/sensor_base.hpp diff --git a/src/components/base_classes/sensor_base_tfs.hpp b/src/components/base/sensor_base_tfs.hpp similarity index 100% rename from src/components/base_classes/sensor_base_tfs.hpp rename to src/components/base/sensor_base_tfs.hpp diff --git a/src/components/cdh/obc.hpp b/src/components/cdh/obc.hpp index 99237238f..4bbff7384 100644 --- a/src/components/cdh/obc.hpp +++ b/src/components/cdh/obc.hpp @@ -11,7 +11,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /* * @class OBC diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 15fcc3329..942e4b5f1 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /** * @class ExampleChangeStructure diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 5319be4dd..1bf5f97cd 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -8,8 +8,8 @@ #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/i2c_controller_communication_base.hpp" +#include "../base/component_base.hpp" +#include "../base/i2c_controller_communication_base.hpp" /** * @class ExampleI2cControllerForHils diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index f2b3029ce..335531a76 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -8,8 +8,8 @@ #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/obc_i2c_target_communication_base.hpp" +#include "../base/component_base.hpp" +#include "../base/obc_i2c_target_communication_base.hpp" /** * @class ExampleI2cTargetForHils diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 58be3e357..61e5aeb2d 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -8,8 +8,8 @@ #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/obc_communication_base.hpp" +#include "../base/component_base.hpp" +#include "../base/obc_communication_base.hpp" /** * @class ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 3b4835ece..8a8222022 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -8,9 +8,9 @@ #include -#include "../base_classes/component_base.hpp" -#include "../base_classes/interface_gpio_component.hpp" -#include "../base_classes/obc_communication_base.hpp" +#include "../base/component_base.hpp" +#include "../base/interface_gpio_component.hpp" +#include "../base/obc_communication_base.hpp" /** * @class ExampleSerialCommunicationWithObc diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index c801ab3c2..c71124118 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ -#include +#include #include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 26db28950..0e2680bc1 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ -#include +#include #include #include #include diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 622bff9ce..612e71a62 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ #define S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ -#include +#include #include #include #include diff --git a/src/components/power/battery.hpp b/src/components/power/battery.hpp index 1d0fa649d..02c89945c 100644 --- a/src/components/power/battery.hpp +++ b/src/components/power/battery.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /* * @class BAT diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index d21597279..02f721bef 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" #include "battery.hpp" #include "solar_array_panel.hpp" diff --git a/src/components/power/power_control_unit.hpp b/src/components/power/power_control_unit.hpp index bf6ce95fd..51665fbd3 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/power/power_control_unit.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /* * @class PCU diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index 438eb64fa..f7ba870d4 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -11,7 +11,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" class SAP : public ComponentBase, public ILoggable { public: diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 06145db0f..7461e613a 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base_classes/component_base.hpp" +#include "../base/component_base.hpp" /* * @class SimpleThruster diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 8fd7e576d..91714fe67 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ #define S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ -#include +#include #include #include "simulation_time.hpp" diff --git a/src/interface/hils/com_port_interface.hpp b/src/interface/hils/com_port_interface.hpp index d8fc9d0bc..e53587f3a 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/interface/hils/com_port_interface.hpp @@ -11,7 +11,7 @@ #include #include -#include +#include #include using namespace System; diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/interface/sils/ports/gpio_port.hpp index 80f07d47f..e645a4fd9 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/interface/sils/ports/gpio_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ #define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ -#include +#include #define GPIO_HIGH true #define GPIO_LOW false From 2cf2b73d50912776b9c77110a7b106a3391a472a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:11:42 +0100 Subject: [PATCH 0379/1086] Rename component_base --- src/components/CMakeLists.txt | 2 +- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel.hpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- src/components/base/{component_base.cpp => component.cpp} | 4 ++-- src/components/base/{component_base.hpp => component.hpp} | 8 ++++---- src/components/cdh/obc.hpp | 2 +- src/components/examples/example_change_structure.hpp | 2 +- .../examples/example_i2c_controller_for_hils.hpp | 2 +- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 2 +- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/mission/telescope.hpp | 2 +- src/components/power/battery.hpp | 2 +- src/components/power/pcu_initial_study.hpp | 2 +- src/components/power/power_control_unit.hpp | 2 +- src/components/power/solar_array_panel.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- 24 files changed, 28 insertions(+), 28 deletions(-) rename src/components/base/{component_base.cpp => component.cpp} (96%) rename src/components/base/{component_base.hpp => component.hpp} (93%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 798d9e5e7..f6b521fcf 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -2,7 +2,7 @@ project(COMPONENT) cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC - base/component_base.cpp + base/component.cpp base/obc_communication_base.cpp base/i2c_controller_communication_base.cpp base/obc_i2c_target_communication_base.cpp diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index a1c848636..d12ff9db5 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" using libra::Vector; diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index 823634c7e..7fa79d7c8 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/sensor_base.hpp" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 5cdd1d1ee..00e352309 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/sensor_base.hpp" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 3b0700908..4848ca3e2 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -14,7 +14,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" const size_t kMtqDim = 3; //!< Dimension of magnetorquer diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index ff0969170..603e72497 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "reaction_wheel_jitter.hpp" #include "reaction_wheel_ode.hpp" diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 2531fa9fb..25729437a 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -15,7 +15,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "dynamics/dynamics.hpp" /* diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 151b6cc54..9166039db 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /* * @class SunSensor diff --git a/src/components/base/component_base.cpp b/src/components/base/component.cpp similarity index 96% rename from src/components/base/component_base.cpp rename to src/components/base/component.cpp index 1038b7244..68957ef96 100644 --- a/src/components/base/component_base.cpp +++ b/src/components/base/component.cpp @@ -1,9 +1,9 @@ /** - * @file component_base.cpp + * @file component.cpp * @brief Base class for component emulation. All components have to inherit this. */ -#include "component_base.hpp" +#include "component.hpp" ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler) : clock_gen_(clock_gen) { power_port_ = new PowerPort(); diff --git a/src/components/base/component_base.hpp b/src/components/base/component.hpp similarity index 93% rename from src/components/base/component_base.hpp rename to src/components/base/component.hpp index bee09392a..a7cfcbaa8 100644 --- a/src/components/base/component_base.hpp +++ b/src/components/base/component.hpp @@ -1,10 +1,10 @@ /** - * @file component_base.hpp + * @file component.hpp * @brief Base class for component emulation. All components have to inherit this. */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_COMPONENT_HPP_ +#define S2E_COMPONENTS_BASE_COMPONENT_HPP_ #include #include @@ -88,4 +88,4 @@ class ComponentBase : public ITickable { PowerPort* power_port_; //!< Power port }; -#endif // S2E_COMPONENTS_BASE_CLASSES_COMPONENT_BASE_HPP_ +#endif // S2E_COMPONENTS_BASE_COMPONENT_HPP_ diff --git a/src/components/cdh/obc.hpp b/src/components/cdh/obc.hpp index 4bbff7384..ee3555f6c 100644 --- a/src/components/cdh/obc.hpp +++ b/src/components/cdh/obc.hpp @@ -11,7 +11,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /* * @class OBC diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 942e4b5f1..0f89abbc8 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /** * @class ExampleChangeStructure diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 1bf5f97cd..5c04c7e2b 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -8,7 +8,7 @@ #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/i2c_controller_communication_base.hpp" /** diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 335531a76..138b9c68e 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -8,7 +8,7 @@ #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/obc_i2c_target_communication_base.hpp" /** diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 61e5aeb2d..add9513a5 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -8,7 +8,7 @@ #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/obc_communication_base.hpp" /** diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 8a8222022..65377547e 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -8,7 +8,7 @@ #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "../base/interface_gpio_component.hpp" #include "../base/obc_communication_base.hpp" diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index c71124118..c8ecc0955 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ -#include +#include #include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index 0e2680bc1..de2e4bd89 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ #define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ -#include +#include #include #include #include diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 612e71a62..289edff4a 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ #define S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ -#include +#include #include #include #include diff --git a/src/components/power/battery.hpp b/src/components/power/battery.hpp index 02c89945c..ffaccb4cd 100644 --- a/src/components/power/battery.hpp +++ b/src/components/power/battery.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /* * @class BAT diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index 02f721bef..6e81efcd2 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -9,7 +9,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" #include "battery.hpp" #include "solar_array_panel.hpp" diff --git a/src/components/power/power_control_unit.hpp b/src/components/power/power_control_unit.hpp index 51665fbd3..c83ba7add 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/power/power_control_unit.hpp @@ -10,7 +10,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /* * @class PCU diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index f7ba870d4..6d6e520d4 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -11,7 +11,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" class SAP : public ComponentBase, public ILoggable { public: diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 7461e613a..eed496447 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -13,7 +13,7 @@ #include #include -#include "../base/component_base.hpp" +#include "../base/component.hpp" /* * @class SimpleThruster From 663158e15edde9354d53338f0a6c49175c632331 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:15:10 +0100 Subject: [PATCH 0380/1086] Rename initialize_sensor --- src/components/aocs/initialize_gyro_sensor.cpp | 2 +- src/components/aocs/initialize_magnetometer.cpp | 2 +- ...nitialize_sensor_base.hpp => initialize_sensor.hpp} | 10 +++++----- ...fs.hpp => initialize_sensor_template_functions.hpp} | 8 ++++---- 4 files changed, 11 insertions(+), 11 deletions(-) rename src/components/base/{initialize_sensor_base.hpp => initialize_sensor.hpp} (72%) rename src/components/base/{initialize_sensor_base_tfs.hpp => initialize_sensor_template_functions.hpp} (88%) diff --git a/src/components/aocs/initialize_gyro_sensor.cpp b/src/components/aocs/initialize_gyro_sensor.cpp index a2bd8fafd..49e59dad0 100644 --- a/src/components/aocs/initialize_gyro_sensor.cpp +++ b/src/components/aocs/initialize_gyro_sensor.cpp @@ -6,7 +6,7 @@ #include -#include "../base/initialize_sensor_base.hpp" +#include "../base/initialize_sensor.hpp" Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); diff --git a/src/components/aocs/initialize_magnetometer.cpp b/src/components/aocs/initialize_magnetometer.cpp index f0efd5647..959c62b56 100644 --- a/src/components/aocs/initialize_magnetometer.cpp +++ b/src/components/aocs/initialize_magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "initialize_magnetometer.hpp" -#include "../base/initialize_sensor_base.hpp" +#include "../base/initialize_sensor.hpp" #include "interface/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { diff --git a/src/components/base/initialize_sensor_base.hpp b/src/components/base/initialize_sensor.hpp similarity index 72% rename from src/components/base/initialize_sensor_base.hpp rename to src/components/base/initialize_sensor.hpp index b8fbec8e5..44e66d112 100644 --- a/src/components/base/initialize_sensor_base.hpp +++ b/src/components/base/initialize_sensor.hpp @@ -1,10 +1,10 @@ /** - * @file initialize_sensor_base.hpp + * @file initialize_sensor.hpp * @brief Initialize functions for SensorBase class */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ +#define S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ #include "sensor_base.hpp" @@ -21,6 +21,6 @@ template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit = ""); -#include "initialize_sensor_base_tfs.hpp" +#include "initialize_sensor_template_functions.hpp" -#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_HPP_ +#endif // S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ diff --git a/src/components/base/initialize_sensor_base_tfs.hpp b/src/components/base/initialize_sensor_template_functions.hpp similarity index 88% rename from src/components/base/initialize_sensor_base_tfs.hpp rename to src/components/base/initialize_sensor_template_functions.hpp index 1815c850a..f0925f032 100644 --- a/src/components/base/initialize_sensor_base_tfs.hpp +++ b/src/components/base/initialize_sensor_template_functions.hpp @@ -1,10 +1,10 @@ /** - * @file initialize_sensor_base_tfs.hpp + * @file initialize_sensor_template_functions.hpp * @brief Initialize functions for SensorBase class (template functions) */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ +#ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ #include "interface/initialize/initialize_file_access.hpp" @@ -51,4 +51,4 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl return sensor_base; } -#endif // S2E_COMPONENTS_BASE_CLASSES_INITIALIZE_SENSOR_BASE_TFS_HPP_ +#endif // S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ From 4692fe4dd65c5d7287909fa7173de3b3f608c123 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:17:50 +0100 Subject: [PATCH 0381/1086] Rename obc_communication_base --- src/components/CMakeLists.txt | 2 +- src/components/base/i2c_controller_communication_base.hpp | 2 +- src/components/base/obc_i2c_target_communication_base.hpp | 2 +- ...unication_base.cpp => uart_communication_with_obc.cpp} | 4 ++-- ...unication_base.hpp => uart_communication_with_obc.hpp} | 8 ++++---- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 2 +- 7 files changed, 11 insertions(+), 11 deletions(-) rename src/components/base/{obc_communication_base.cpp => uart_communication_with_obc.cpp} (98%) rename src/components/base/{obc_communication_base.hpp => uart_communication_with_obc.hpp} (95%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f6b521fcf..58cfa64a8 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC base/component.cpp - base/obc_communication_base.cpp + base/uart_communication_with_obc.cpp base/i2c_controller_communication_base.cpp base/obc_i2c_target_communication_base.cpp base/obc_gpio_base.cpp diff --git a/src/components/base/i2c_controller_communication_base.hpp b/src/components/base/i2c_controller_communication_base.hpp index fc09af8a2..a5ee3f900 100644 --- a/src/components/base/i2c_controller_communication_base.hpp +++ b/src/components/base/i2c_controller_communication_base.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ #include "../../interface/hils/hils_port_manager.hpp" -#include "obc_communication_base.hpp" +#include "uart_communication_with_obc.hpp" /** * @class I2cControllerCommunicationBase diff --git a/src/components/base/obc_i2c_target_communication_base.hpp b/src/components/base/obc_i2c_target_communication_base.hpp index f3ffe5b9c..6ba8bf558 100644 --- a/src/components/base/obc_i2c_target_communication_base.hpp +++ b/src/components/base/obc_i2c_target_communication_base.hpp @@ -8,7 +8,7 @@ #include "../../interface/hils/hils_port_manager.hpp" #include "../cdh/obc.hpp" -#include "obc_communication_base.hpp" +#include "uart_communication_with_obc.hpp" /** * @class ObcI2cTargetCommunicationBase diff --git a/src/components/base/obc_communication_base.cpp b/src/components/base/uart_communication_with_obc.cpp similarity index 98% rename from src/components/base/obc_communication_base.cpp rename to src/components/base/uart_communication_with_obc.cpp index 21df9bf6e..7b7f272fc 100644 --- a/src/components/base/obc_communication_base.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -1,9 +1,9 @@ /** - * @file obc_communication_base.cpp + * @file uart_communication_with_obc.cpp * @brief Base class for serial communication (e.g., UART) with OBC flight software */ -#include "obc_communication_base.hpp" +#include "uart_communication_with_obc.hpp" #include diff --git a/src/components/base/obc_communication_base.hpp b/src/components/base/uart_communication_with_obc.hpp similarity index 95% rename from src/components/base/obc_communication_base.hpp rename to src/components/base/uart_communication_with_obc.hpp index 5282f795c..990b11319 100644 --- a/src/components/base/obc_communication_base.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -1,10 +1,10 @@ /** - * @file obc_communication_base.hpp + * @file uart_communication_with_obc.hpp * @brief Base class for serial communication (e.g., UART) with OBC flight software */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ +#define S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ #include @@ -128,4 +128,4 @@ class ObcCommunicationBase { virtual int GenerateTelemetry() = 0; }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_COMMUNICATION_BASE_HPP_ +#endif // S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index add9513a5..864d81e21 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -9,7 +9,7 @@ #include #include "../base/component.hpp" -#include "../base/obc_communication_base.hpp" +#include "../base/uart_communication_with_obc.hpp" /** * @class ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 65377547e..4e178166c 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -10,7 +10,7 @@ #include "../base/component.hpp" #include "../base/interface_gpio_component.hpp" -#include "../base/obc_communication_base.hpp" +#include "../base/uart_communication_with_obc.hpp" /** * @class ExampleSerialCommunicationWithObc From e384f1f0bc8199f2cb61ad8e668902daeb2110d8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:20:34 +0100 Subject: [PATCH 0382/1086] Rename obc_gpio_base --- src/components/CMakeLists.txt | 2 +- .../{obc_gpio_base.cpp => gpio_connection_with_obc.cpp} | 4 ++-- .../{obc_gpio_base.hpp => gpio_connection_with_obc.hpp} | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) rename src/components/base/{obc_gpio_base.cpp => gpio_connection_with_obc.cpp} (87%) rename src/components/base/{obc_gpio_base.hpp => gpio_connection_with_obc.hpp} (86%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 58cfa64a8..d102644d0 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -6,7 +6,7 @@ add_library(${PROJECT_NAME} STATIC base/uart_communication_with_obc.cpp base/i2c_controller_communication_base.cpp base/obc_i2c_target_communication_base.cpp - base/obc_gpio_base.cpp + base/gpio_connection_with_obc.cpp aocs/gyro_sensor.cpp aocs/initialize_gyro_sensor.cpp diff --git a/src/components/base/obc_gpio_base.cpp b/src/components/base/gpio_connection_with_obc.cpp similarity index 87% rename from src/components/base/obc_gpio_base.cpp rename to src/components/base/gpio_connection_with_obc.cpp index a2151a1f0..6f74b68fe 100644 --- a/src/components/base/obc_gpio_base.cpp +++ b/src/components/base/gpio_connection_with_obc.cpp @@ -1,10 +1,10 @@ /** - * @file obc_gpio_base.cpp + * @file gpio_connection_with_obc.cpp * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ -#include "obc_gpio_base.hpp" +#include "gpio_connection_with_obc.hpp" ObcGpioBase::ObcGpioBase(const std::vector port_id, OBC* obc) : port_id_(port_id), obc_(obc) { for (size_t i = 0; i < port_id_.size(); i++) { diff --git a/src/components/base/obc_gpio_base.hpp b/src/components/base/gpio_connection_with_obc.hpp similarity index 86% rename from src/components/base/obc_gpio_base.hpp rename to src/components/base/gpio_connection_with_obc.hpp index 282efa638..81a4ab2ba 100644 --- a/src/components/base/obc_gpio_base.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -1,11 +1,11 @@ /** - * @file obc_gpio_base.hpp + * @file gpio_connection_with_obc.hpp * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ +#ifndef S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ +#define S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ #include "../cdh/obc.hpp" @@ -50,4 +50,4 @@ class ObcGpioBase { OBC* obc_; //!< The communication target OBC }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_GPIO_BASE_HPP_ +#endif // S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ From 5615716402ff1bd50f5f09866c3f752729a78ede Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:23:45 +0100 Subject: [PATCH 0383/1086] Rename sensor_base --- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/base/initialize_sensor.hpp | 2 +- src/components/base/{sensor_base.hpp => sensor.hpp} | 10 +++++----- ...nsor_base_tfs.hpp => sensor_template_functions.hpp} | 8 ++++---- 5 files changed, 12 insertions(+), 12 deletions(-) rename src/components/base/{sensor_base.hpp => sensor.hpp} (91%) rename src/components/base/{sensor_base_tfs.hpp => sensor_template_functions.hpp} (92%) diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index 7fa79d7c8..1decc4a1d 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -11,7 +11,7 @@ #include #include "../base/component.hpp" -#include "../base/sensor_base.hpp" +#include "../base/sensor.hpp" const size_t kGyroDim = 3; //!< Dimension of gyro sensor diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 00e352309..2da001925 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -11,7 +11,7 @@ #include #include "../base/component.hpp" -#include "../base/sensor_base.hpp" +#include "../base/sensor.hpp" const size_t kMagDim = 3; //!< Dimension of magnetometer diff --git a/src/components/base/initialize_sensor.hpp b/src/components/base/initialize_sensor.hpp index 44e66d112..8aa1eab2b 100644 --- a/src/components/base/initialize_sensor.hpp +++ b/src/components/base/initialize_sensor.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ #define S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ -#include "sensor_base.hpp" +#include "sensor.hpp" /** * @fn ReadSensorBaseInformation diff --git a/src/components/base/sensor_base.hpp b/src/components/base/sensor.hpp similarity index 91% rename from src/components/base/sensor_base.hpp rename to src/components/base/sensor.hpp index 2559db33f..d6d1627d6 100644 --- a/src/components/base/sensor_base.hpp +++ b/src/components/base/sensor.hpp @@ -1,10 +1,10 @@ /** - * @file sensor_base.hpp + * @file sensor.hpp * @brief Base class for sensor emulation to add noises */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_SENSOR_HPP_ +#define S2E_COMPONENTS_BASE_SENSOR_HPP_ #include #include @@ -71,6 +71,6 @@ class SensorBase { void RangeCheck(void); }; -#include "./sensor_base_tfs.hpp" // template function definisions. +#include "./sensor_template_functions.hpp" -#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_HPP_ \ No newline at end of file +#endif // S2E_COMPONENTS_BASE_SENSOR_HPP_ diff --git a/src/components/base/sensor_base_tfs.hpp b/src/components/base/sensor_template_functions.hpp similarity index 92% rename from src/components/base/sensor_base_tfs.hpp rename to src/components/base/sensor_template_functions.hpp index 34415e208..0bcee54d1 100644 --- a/src/components/base/sensor_base_tfs.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -1,10 +1,10 @@ /** - * @file sensor_base_tfs.hpp + * @file sensor_template_functions.hpp * @brief Base class for sensor emulation to add noises */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ +#ifndef S2E_COMPONENTS_BASE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_COMPONENTS_BASE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ #include @@ -73,4 +73,4 @@ void SensorBase::RangeCheck(void) { } } -#endif // S2E_COMPONENTS_BASE_CLASSES_SENSOR_BASE_TFS_HPP_ \ No newline at end of file +#endif // S2E_COMPONENTS_BASE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ From a2b9c469d9f6b594c516f7801ae4d386eb13bea1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:28:25 +0100 Subject: [PATCH 0384/1086] Rename i2c_controller_communication_base --- src/components/CMakeLists.txt | 2 +- ...ntroller_communication_base.cpp => i2c_controller.cpp} | 4 ++-- ...ntroller_communication_base.hpp => i2c_controller.hpp} | 8 ++++---- .../examples/example_i2c_controller_for_hils.hpp | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) rename src/components/base/{i2c_controller_communication_base.cpp => i2c_controller.cpp} (94%) rename src/components/base/{i2c_controller_communication_base.hpp => i2c_controller.hpp} (90%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index d102644d0..3f5b60338 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -4,7 +4,7 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC base/component.cpp base/uart_communication_with_obc.cpp - base/i2c_controller_communication_base.cpp + base/i2c_controller.cpp base/obc_i2c_target_communication_base.cpp base/gpio_connection_with_obc.cpp diff --git a/src/components/base/i2c_controller_communication_base.cpp b/src/components/base/i2c_controller.cpp similarity index 94% rename from src/components/base/i2c_controller_communication_base.cpp rename to src/components/base/i2c_controller.cpp index 5b42929d2..2069417e8 100644 --- a/src/components/base/i2c_controller_communication_base.cpp +++ b/src/components/base/i2c_controller.cpp @@ -1,8 +1,8 @@ /** - * @file i2c_controller_communication_base.cpp + * @file i2c_controller.cpp * @brief This class simulates the I2C Controller communication with the I2C Target. */ -#include "i2c_controller_communication_base.hpp" +#include "i2c_controller.hpp" #include diff --git a/src/components/base/i2c_controller_communication_base.hpp b/src/components/base/i2c_controller.hpp similarity index 90% rename from src/components/base/i2c_controller_communication_base.hpp rename to src/components/base/i2c_controller.hpp index a5ee3f900..aa25b6a7a 100644 --- a/src/components/base/i2c_controller_communication_base.hpp +++ b/src/components/base/i2c_controller.hpp @@ -1,10 +1,10 @@ /** - * @file i2c_controller_communication_base.hpp + * @file i2c_controller.hpp * @brief This class simulates the I2C Controller communication with the I2C Target. */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_I2C_CONTROLLER_HPP_ +#define S2E_COMPONENTS_BASE_I2C_CONTROLLER_HPP_ #include "../../interface/hils/hils_port_manager.hpp" #include "uart_communication_with_obc.hpp" @@ -64,4 +64,4 @@ class I2cControllerCommunicationBase { HilsPortManager* hils_port_manager_; //!< HILS port manager }; -#endif // S2E_COMPONENTS_BASE_CLASSES_I2C_CONTROLLER_COMMUNICATION_BASE_HPP_ +#endif // S2E_COMPONENTS_BASE_I2C_CONTROLLER_HPP_ diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 5c04c7e2b..92ea8119d 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -9,7 +9,7 @@ #include #include "../base/component.hpp" -#include "../base/i2c_controller_communication_base.hpp" +#include "../base/i2c_controller.hpp" /** * @class ExampleI2cControllerForHils From c804881d3f69f136b9959cce7b1c114e1dd9ffd1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 9 Feb 2023 22:30:49 +0100 Subject: [PATCH 0385/1086] Rename obc_i2c_target_communication_base --- src/components/CMakeLists.txt | 2 +- ...ion_base.cpp => i2c_target_communication_with_obc.cpp} | 4 ++-- ...ion_base.hpp => i2c_target_communication_with_obc.hpp} | 8 ++++---- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) rename src/components/base/{obc_i2c_target_communication_base.cpp => i2c_target_communication_with_obc.cpp} (98%) rename src/components/base/{obc_i2c_target_communication_base.hpp => i2c_target_communication_with_obc.hpp} (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 3f5b60338..24e290bc8 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -5,7 +5,7 @@ add_library(${PROJECT_NAME} STATIC base/component.cpp base/uart_communication_with_obc.cpp base/i2c_controller.cpp - base/obc_i2c_target_communication_base.cpp + base/i2c_target_communication_with_obc.cpp base/gpio_connection_with_obc.cpp aocs/gyro_sensor.cpp diff --git a/src/components/base/obc_i2c_target_communication_base.cpp b/src/components/base/i2c_target_communication_with_obc.cpp similarity index 98% rename from src/components/base/obc_i2c_target_communication_base.cpp rename to src/components/base/i2c_target_communication_with_obc.cpp index a56b57df3..8db952d68 100644 --- a/src/components/base/obc_i2c_target_communication_base.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -1,8 +1,8 @@ /** - * @file obc_i2c_target_communication_base.cpp + * @file i2c_target_communication_with_obc.cpp * @brief Base class for I2C communication as target side with OBC flight software */ -#include "obc_i2c_target_communication_base.hpp" +#include "i2c_target_communication_with_obc.hpp" #include diff --git a/src/components/base/obc_i2c_target_communication_base.hpp b/src/components/base/i2c_target_communication_with_obc.hpp similarity index 94% rename from src/components/base/obc_i2c_target_communication_base.hpp rename to src/components/base/i2c_target_communication_with_obc.hpp index 6ba8bf558..27be4d61c 100644 --- a/src/components/base/obc_i2c_target_communication_base.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -1,10 +1,10 @@ /** - * @file obc_i2c_target_communication_base.hpp + * @file i2c_target_communication_with_obc.hpp * @brief Base class for I2C communication as target side with OBC flight software */ -#ifndef S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ -#define S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ +#ifndef S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ +#define S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ #include "../../interface/hils/hils_port_manager.hpp" #include "../cdh/obc.hpp" @@ -121,4 +121,4 @@ class ObcI2cTargetCommunicationBase { HilsPortManager* hils_port_manager_; //!< HILS port manager }; -#endif // S2E_COMPONENTS_BASE_CLASSES_OBC_I2C_TARGET_COMMUNICATION_BASE_HPP_ +#endif // S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 138b9c68e..79b22eac1 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -9,7 +9,7 @@ #include #include "../base/component.hpp" -#include "../base/obc_i2c_target_communication_base.hpp" +#include "../base/i2c_target_communication_with_obc.hpp" /** * @class ExampleI2cTargetForHils From ec7e82ef1562c55ed964726eb23626894ff6cd26 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:23:59 +0100 Subject: [PATCH 0386/1086] Move sgp4 and igrf --- .../initialize_files/sample_local_environment.ini | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 4 ++-- src/environment/global/celestial_rotation.cpp | 4 ++-- src/environment/global/gnss_satellites.cpp | 4 ++-- src/environment/global/simulation_time.hpp | 6 +++--- src/environment/local/geomagnetic_field.cpp | 2 +- src/library/CMakeLists.txt | 9 ++++----- src/library/{ => external}/igrf/igrf.cpp | 12 ++++++------ src/library/{ => external}/igrf/igrf.h | 0 src/library/{ => external}/igrf/igrf11.coef | 0 src/library/{ => external}/igrf/igrf12.coef | 0 src/library/{ => external}/igrf/igrf13.coef | 0 src/library/{ => external}/sgp4/sgp4ext.cpp | 0 src/library/{ => external}/sgp4/sgp4ext.h | 0 src/library/{ => external}/sgp4/sgp4io.cpp | 0 src/library/{ => external}/sgp4/sgp4io.h | 0 src/library/{ => external}/sgp4/sgp4unit.cpp | 0 src/library/{ => external}/sgp4/sgp4unit.h | 0 src/library/geodesy/geodetic_position.cpp | 2 +- 19 files changed, 22 insertions(+), 23 deletions(-) rename src/library/{ => external}/igrf/igrf.cpp (97%) rename src/library/{ => external}/igrf/igrf.h (100%) rename src/library/{ => external}/igrf/igrf11.coef (100%) rename src/library/{ => external}/igrf/igrf12.coef (100%) rename src/library/{ => external}/igrf/igrf13.coef (100%) rename src/library/{ => external}/sgp4/sgp4ext.cpp (100%) rename src/library/{ => external}/sgp4/sgp4ext.h (100%) rename src/library/{ => external}/sgp4/sgp4io.cpp (100%) rename src/library/{ => external}/sgp4/sgp4io.h (100%) rename src/library/{ => external}/sgp4/sgp4unit.cpp (100%) rename src/library/{ => external}/sgp4/sgp4unit.h (100%) diff --git a/data/sample/initialize_files/sample_local_environment.ini b/data/sample/initialize_files/sample_local_environment.ini index 2f4829223..06faad3bd 100644 --- a/data/sample/initialize_files/sample_local_environment.ini +++ b/data/sample/initialize_files/sample_local_environment.ini @@ -1,7 +1,7 @@ [MAGNETIC_FIELD_ENVIRONMENT] calculation = ENABLE logging = ENABLE -coefficient_file = ../../../s2e-core/src/library/igrf/igrf13.coef +coefficient_file = ../../../s2e-core/src/library/external/igrf/igrf13.coef magnetic_field_random_walk_speed_nT = 10.0 magnetic_field_random_walk_limit_nT = 400.0 magnetic_field_white_noise_standard_deviation_nT = 50.0 diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 7ddd177ae..823f69221 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -6,8 +6,8 @@ #ifndef S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ #define S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ -#include -#include +#include +#include #include diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index a0e3adbe2..8e343817a 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -9,8 +9,8 @@ #include "celestial_rotation.hpp" -#include // for jday() -#include // for gstime() +#include // for jday() +#include // for gstime() #include #include diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index c23b4de10..a70e53144 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,8 +5,8 @@ #include "gnss_satellites.hpp" -#include //for jday() -#include //for gstime() +#include //for jday() +#include //for gstime() #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 75a5df921..434796da2 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,9 +12,9 @@ #include // #include -#include -#include -#include +#include +#include +#include #include #include diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 064b8e57a..2cbed90c6 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,7 +5,7 @@ #include "geomagnetic_field.hpp" -#include +#include #include #include diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index b98ff8c76..76fede5ff 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -3,8 +3,6 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC geodesy/geodetic_position.cpp - - igrf/igrf.cpp inih/ini.c inih/cpp/INIReader.cpp @@ -26,9 +24,10 @@ add_library(${PROJECT_NAME} STATIC orbit/kepler_orbit.cpp orbit/relative_orbit_models.cpp - sgp4/sgp4ext.cpp - sgp4/sgp4io.cpp - sgp4/sgp4unit.cpp + external/sgp4/sgp4ext.cpp + external/sgp4/sgp4io.cpp + external/sgp4/sgp4unit.cpp + external/igrf/igrf.cpp utilities/endian.cpp utilities/slip.cpp diff --git a/src/library/igrf/igrf.cpp b/src/library/external/igrf/igrf.cpp similarity index 97% rename from src/library/igrf/igrf.cpp rename to src/library/external/igrf/igrf.cpp index 9f2468eda..0b926088a 100644 --- a/src/library/igrf/igrf.cpp +++ b/src/library/external/igrf/igrf.cpp @@ -297,12 +297,12 @@ void gigrf(int gen, double year) { // char file[]="igrf10.coef"; // char path[] = "igrf11.coef"; // char file[] = "igrf11.coef"; - // char path[] = "src/library/igrf/igrf11.coef"; - // char file[] = "src/library/igrf/igrf11.coef"; - // char path[] = "../SatAttSim/src/library/igrf/igrf12.coef"; - // char file[] = "../SatAttSim/src/library/igrf/igrf12.coef"; - // char path[] = "../../SatAttSim/src/library/igrf/igrf13.coef"; //from 2020 - // char file[] = "../../SatAttSim/src/library/igrf/igrf13.coef"; //from 2020 + // char path[] = "src/library/external/igrf/igrf11.coef"; + // char file[] = "src/library/external/igrf/igrf11.coef"; + // char path[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; + // char file[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; + // char path[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 + // char file[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 char file[256]; diff --git a/src/library/igrf/igrf.h b/src/library/external/igrf/igrf.h similarity index 100% rename from src/library/igrf/igrf.h rename to src/library/external/igrf/igrf.h diff --git a/src/library/igrf/igrf11.coef b/src/library/external/igrf/igrf11.coef similarity index 100% rename from src/library/igrf/igrf11.coef rename to src/library/external/igrf/igrf11.coef diff --git a/src/library/igrf/igrf12.coef b/src/library/external/igrf/igrf12.coef similarity index 100% rename from src/library/igrf/igrf12.coef rename to src/library/external/igrf/igrf12.coef diff --git a/src/library/igrf/igrf13.coef b/src/library/external/igrf/igrf13.coef similarity index 100% rename from src/library/igrf/igrf13.coef rename to src/library/external/igrf/igrf13.coef diff --git a/src/library/sgp4/sgp4ext.cpp b/src/library/external/sgp4/sgp4ext.cpp similarity index 100% rename from src/library/sgp4/sgp4ext.cpp rename to src/library/external/sgp4/sgp4ext.cpp diff --git a/src/library/sgp4/sgp4ext.h b/src/library/external/sgp4/sgp4ext.h similarity index 100% rename from src/library/sgp4/sgp4ext.h rename to src/library/external/sgp4/sgp4ext.h diff --git a/src/library/sgp4/sgp4io.cpp b/src/library/external/sgp4/sgp4io.cpp similarity index 100% rename from src/library/sgp4/sgp4io.cpp rename to src/library/external/sgp4/sgp4io.cpp diff --git a/src/library/sgp4/sgp4io.h b/src/library/external/sgp4/sgp4io.h similarity index 100% rename from src/library/sgp4/sgp4io.h rename to src/library/external/sgp4/sgp4io.h diff --git a/src/library/sgp4/sgp4unit.cpp b/src/library/external/sgp4/sgp4unit.cpp similarity index 100% rename from src/library/sgp4/sgp4unit.cpp rename to src/library/external/sgp4/sgp4unit.cpp diff --git a/src/library/sgp4/sgp4unit.h b/src/library/external/sgp4/sgp4unit.h similarity index 100% rename from src/library/sgp4/sgp4unit.h rename to src/library/external/sgp4/sgp4unit.h diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 8ae62a9c9..4f0478f5b 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -4,7 +4,7 @@ */ #include "geodetic_position.hpp" -#include // TODO: do not to use the functions in SGP4 library +#include // TODO: do not to use the functions in SGP4 library #include #include From 622fc0e850d01cae6dafb9540b614fd4f7f16a94 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:26:57 +0100 Subject: [PATCH 0387/1086] Move nrlmsise00 --- src/environment/local/atmosphere.hpp | 2 +- src/library/CMakeLists.txt | 5 ++--- src/library/{ => external}/nrlmsise00/wrapper_nrlmsise00.cpp | 0 src/library/{ => external}/nrlmsise00/wrapper_nrlmsise00.hpp | 0 4 files changed, 3 insertions(+), 4 deletions(-) rename src/library/{ => external}/nrlmsise00/wrapper_nrlmsise00.cpp (100%) rename src/library/{ => external}/nrlmsise00/wrapper_nrlmsise00.hpp (100%) diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 519e28a47..43f1d0a2f 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 76fede5ff..5bd445cdc 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -16,18 +16,17 @@ add_library(${PROJECT_NAME} STATIC math/vector.cpp math/s2e_math.cpp - nrlmsise00/wrapper_nrlmsise00.cpp - optics/gaussian_beam_base.cpp orbit/orbital_elements.cpp orbit/kepler_orbit.cpp orbit/relative_orbit_models.cpp + external/igrf/igrf.cpp + external/nrlmsise00/wrapper_nrlmsise00.cpp external/sgp4/sgp4ext.cpp external/sgp4/sgp4io.cpp external/sgp4/sgp4unit.cpp - external/igrf/igrf.cpp utilities/endian.cpp utilities/slip.cpp diff --git a/src/library/nrlmsise00/wrapper_nrlmsise00.cpp b/src/library/external/nrlmsise00/wrapper_nrlmsise00.cpp similarity index 100% rename from src/library/nrlmsise00/wrapper_nrlmsise00.cpp rename to src/library/external/nrlmsise00/wrapper_nrlmsise00.cpp diff --git a/src/library/nrlmsise00/wrapper_nrlmsise00.hpp b/src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp similarity index 100% rename from src/library/nrlmsise00/wrapper_nrlmsise00.hpp rename to src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp From 082ad1badc6b57198ca1ec5fa2f0cac41a9c8938 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:28:24 +0100 Subject: [PATCH 0388/1086] Move inih --- src/interface/initialize/initialize_file_access.hpp | 2 +- src/library/CMakeLists.txt | 5 ++--- src/library/{ => external}/inih/LICENSE.txt | 0 src/library/{ => external}/inih/README.md | 0 src/library/{ => external}/inih/cpp/INIReader.cpp | 0 src/library/{ => external}/inih/cpp/INIReader.h | 0 src/library/{ => external}/inih/ini.c | 0 src/library/{ => external}/inih/ini.h | 0 8 files changed, 3 insertions(+), 4 deletions(-) rename src/library/{ => external}/inih/LICENSE.txt (100%) rename src/library/{ => external}/inih/README.md (100%) rename src/library/{ => external}/inih/cpp/INIReader.cpp (100%) rename src/library/{ => external}/inih/cpp/INIReader.h (100%) rename src/library/{ => external}/inih/ini.c (100%) rename src/library/{ => external}/inih/ini.h (100%) diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/interface/initialize/initialize_file_access.hpp index 734322df6..aa9d0f4df 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/interface/initialize/initialize_file_access.hpp @@ -13,7 +13,7 @@ #include #include #else -#include +#include #endif #include #include diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 5bd445cdc..2e96c399a 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -4,9 +4,6 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC geodesy/geodetic_position.cpp - inih/ini.c - inih/cpp/INIReader.cpp - math/global_randomization.cpp math/normal_randomization.cpp math/quantization.cpp @@ -23,6 +20,8 @@ add_library(${PROJECT_NAME} STATIC orbit/relative_orbit_models.cpp external/igrf/igrf.cpp + external/inih/ini.c + external/inih/cpp/INIReader.cpp external/nrlmsise00/wrapper_nrlmsise00.cpp external/sgp4/sgp4ext.cpp external/sgp4/sgp4io.cpp diff --git a/src/library/inih/LICENSE.txt b/src/library/external/inih/LICENSE.txt similarity index 100% rename from src/library/inih/LICENSE.txt rename to src/library/external/inih/LICENSE.txt diff --git a/src/library/inih/README.md b/src/library/external/inih/README.md similarity index 100% rename from src/library/inih/README.md rename to src/library/external/inih/README.md diff --git a/src/library/inih/cpp/INIReader.cpp b/src/library/external/inih/cpp/INIReader.cpp similarity index 100% rename from src/library/inih/cpp/INIReader.cpp rename to src/library/external/inih/cpp/INIReader.cpp diff --git a/src/library/inih/cpp/INIReader.h b/src/library/external/inih/cpp/INIReader.h similarity index 100% rename from src/library/inih/cpp/INIReader.h rename to src/library/external/inih/cpp/INIReader.h diff --git a/src/library/inih/ini.c b/src/library/external/inih/ini.c similarity index 100% rename from src/library/inih/ini.c rename to src/library/external/inih/ini.c diff --git a/src/library/inih/ini.h b/src/library/external/inih/ini.h similarity index 100% rename from src/library/inih/ini.h rename to src/library/external/inih/ini.h From b3f43af93b684fe89419ab981ea9667715c1b52e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:30:49 +0100 Subject: [PATCH 0389/1086] Move quantization --- src/library/CMakeLists.txt | 2 +- src/library/{math => utilities}/quantization.cpp | 0 src/library/{math => utilities}/quantization.hpp | 0 3 files changed, 1 insertion(+), 1 deletion(-) rename src/library/{math => utilities}/quantization.cpp (100%) rename src/library/{math => utilities}/quantization.hpp (100%) diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 2e96c399a..72574ea12 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -6,7 +6,6 @@ add_library(${PROJECT_NAME} STATIC math/global_randomization.cpp math/normal_randomization.cpp - math/quantization.cpp math/quaternion.cpp math/randomize0.cpp math/randomize1.cpp @@ -29,6 +28,7 @@ add_library(${PROJECT_NAME} STATIC utilities/endian.cpp utilities/slip.cpp + utilities/quantization.cpp ) include(../../common.cmake) diff --git a/src/library/math/quantization.cpp b/src/library/utilities/quantization.cpp similarity index 100% rename from src/library/math/quantization.cpp rename to src/library/utilities/quantization.cpp diff --git a/src/library/math/quantization.hpp b/src/library/utilities/quantization.hpp similarity index 100% rename from src/library/math/quantization.hpp rename to src/library/utilities/quantization.hpp From 107e798459b3a471342e0ff76bb3029ced31a5ed Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:32:10 +0100 Subject: [PATCH 0390/1086] Modify include guard --- src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp | 6 +++--- src/library/utilities/quantization.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp b/src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp index e1f3ac39f..7729e6211 100644 --- a/src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp +++ b/src/library/external/nrlmsise00/wrapper_nrlmsise00.hpp @@ -3,8 +3,8 @@ * @brief Functions to wrap NRLMSISE-00 air density model in the Externallibrary */ -#ifndef S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ -#define S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ +#ifndef S2E_LIBRARY_EXTERNAL_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ +#define S2E_LIBRARY_EXTERNAL_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ #include #include @@ -74,4 +74,4 @@ int GetSpaceWeatherTable_(double decyear, double endsec, const std::string& file #define __inline_double double #endif -#endif // S2E_LIBRARY_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ +#endif // S2E_LIBRARY_EXTERNAL_NRLMSISE00_WRAPPER_NRLMSISE00__HPP_ diff --git a/src/library/utilities/quantization.hpp b/src/library/utilities/quantization.hpp index 9ba1bdd06..d164375b3 100644 --- a/src/library/utilities/quantization.hpp +++ b/src/library/utilities/quantization.hpp @@ -3,8 +3,8 @@ * @brief Functions for quantization */ -#ifndef S2E_LIBRARY_MATH_QUANTIZATION_HPP_ -#define S2E_LIBRARY_MATH_QUANTIZATION_HPP_ +#ifndef S2E_LIBRARY_UTILITIES_QUANTIZATION_HPP_ +#define S2E_LIBRARY_UTILITIES_QUANTIZATION_HPP_ /** * @fn quantization @@ -24,4 +24,4 @@ double quantization(double continuous_num, double resolution); */ float quantization_f(double continuous_num, double resolution); -#endif // S2E_LIBRARY_MATH_QUANTIZATION_HPP_ +#endif // S2E_LIBRARY_UTILITIES_QUANTIZATION_HPP_ From ea3f48636f76c7b5ea0a7b346566da66d7f48717 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:47:10 +0100 Subject: [PATCH 0391/1086] Move to randomization --- src/components/aocs/gnss_receiver.cpp | 2 +- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/magnetorquer.hpp | 4 ++-- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/star_sensor.hpp | 4 ++-- src/components/aocs/sun_sensor.cpp | 4 ++-- src/components/aocs/sun_sensor.hpp | 2 +- src/components/base/sensor.hpp | 4 ++-- src/components/base/sensor_template_functions.hpp | 2 +- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/propulsion/simple_thruster.cpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 6 +++--- src/environment/local/atmosphere.cpp | 6 +++--- src/environment/local/geomagnetic_field.cpp | 6 +++--- src/library/CMakeLists.txt | 9 +++++---- .../{math => randomization}/global_randomization.cpp | 0 .../{math => randomization}/global_randomization.hpp | 8 ++++---- ...minimal_standard_linear_congruential_generator.cpp} | 2 +- ...minimal_standard_linear_congruential_generator.hpp} | 2 +- ...ard_linear_congruential_generator_with_shuffle.cpp} | 2 +- ...ard_linear_congruential_generator_with_shuffle.hpp} | 4 ++-- .../{math => randomization}/normal_randomization.cpp | 0 .../{math => randomization}/normal_randomization.hpp | 10 +++++----- .../normal_randomization_inline_functions.hpp} | 0 src/library/{math => randomization}/random_walk.hpp | 6 +++--- .../random_walk_template_functions.hpp} | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 2 +- 30 files changed, 51 insertions(+), 50 deletions(-) rename src/library/{math => randomization}/global_randomization.cpp (100%) rename src/library/{math => randomization}/global_randomization.hpp (77%) rename src/library/{math/randomize0.cpp => randomization/minimal_standard_linear_congruential_generator.cpp} (91%) rename src/library/{math/randomize0.hpp => randomization/minimal_standard_linear_congruential_generator.hpp} (95%) rename src/library/{math/randomize1.cpp => randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp} (91%) rename src/library/{math/randomize1.hpp => randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp} (92%) rename src/library/{math => randomization}/normal_randomization.cpp (100%) rename src/library/{math => randomization}/normal_randomization.hpp (89%) rename src/library/{math/normal_randomization_ifs.hpp => randomization/normal_randomization_inline_functions.hpp} (100%) rename src/library/{math => randomization}/random_walk.hpp (87%) rename src/library/{math/random_walk_tfs.hpp => randomization/random_walk_template_functions.hpp} (94%) diff --git a/src/components/aocs/gnss_receiver.cpp b/src/components/aocs/gnss_receiver.cpp index 6694810a9..449f53ee1 100644 --- a/src/components/aocs/gnss_receiver.cpp +++ b/src/components/aocs/gnss_receiver.cpp @@ -6,7 +6,7 @@ #include "gnss_receiver.hpp" #include -#include +#include #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index d12ff9db5..708a704fd 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 65a2065aa..ceb42e337 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -6,7 +6,7 @@ #include "magnetorquer.hpp" #include -#include +#include #include #include diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index 4848ca3e2..af2404c7d 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -9,9 +9,9 @@ #include #include #include -#include +#include #include -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 30b0b60ea..cad6af5c7 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 25729437a..626e92b2e 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -9,10 +9,10 @@ #include #include #include -#include #include -#include #include +#include +#include #include #include "../base/component.hpp" diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index c2c49d006..ad1b77cca 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -6,10 +6,10 @@ #include "sun_sensor.hpp" #include -#include +#include using libra::NormalRand; #include -#include +#include using namespace std; diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 9166039db..6b87781f8 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index d6d1627d6..9f2712198 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -7,8 +7,8 @@ #define S2E_COMPONENTS_BASE_SENSOR_HPP_ #include -#include -#include +#include +#include #include /** diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index 0bcee54d1..ce02ba2f4 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ #define S2E_COMPONENTS_BASE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ -#include +#include template SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index c8ecc0955..b6473e190 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include /* diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index de2e4bd89..d5f1fa152 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include /* diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/propulsion/simple_thruster.cpp index 5e8727aa2..75d22b852 100644 --- a/src/components/propulsion/simple_thruster.cpp +++ b/src/components/propulsion/simple_thruster.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include // Constructor SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, const int id, const Vector<3> thruster_pos_b, diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index eed496447..7c3bb5064 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index f88998d7a..5672e8490 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -5,13 +5,13 @@ #include "magnetic_disturbance.hpp" -#include "../library/math/normal_randomization.hpp" +#include "../library/randomization/normal_randomization.hpp" using libra::NormalRand; #include #include "../interface/log_output/log_utility.hpp" -#include "../library/math/global_randomization.hpp" -#include "../library/math/random_walk.hpp" +#include "../library/randomization/global_randomization.hpp" +#include "../library/randomization/random_walk.hpp" using namespace std; diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index fc553bbb3..31988e619 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -6,9 +6,9 @@ #include "atmosphere.hpp" #include -#include -#include -#include +#include +#include +#include #include using libra::NormalRand; diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 2cbed90c6..37b837119 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -8,9 +8,9 @@ #include #include -#include -#include -#include +#include +#include +#include using libra::NormalRand; using namespace std; diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 72574ea12..bc93d68aa 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -4,11 +4,12 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC geodesy/geodetic_position.cpp - math/global_randomization.cpp - math/normal_randomization.cpp + randomization/global_randomization.cpp + randomization/normal_randomization.cpp + randomization/minimal_standard_linear_congruential_generator.cpp + randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp + math/quaternion.cpp - math/randomize0.cpp - math/randomize1.cpp math/vector.cpp math/s2e_math.cpp diff --git a/src/library/math/global_randomization.cpp b/src/library/randomization/global_randomization.cpp similarity index 100% rename from src/library/math/global_randomization.cpp rename to src/library/randomization/global_randomization.cpp diff --git a/src/library/math/global_randomization.hpp b/src/library/randomization/global_randomization.hpp similarity index 77% rename from src/library/math/global_randomization.hpp rename to src/library/randomization/global_randomization.hpp index 0f230e146..85f876cc7 100644 --- a/src/library/math/global_randomization.hpp +++ b/src/library/randomization/global_randomization.hpp @@ -3,10 +3,10 @@ * @brief Class to manage global randomization */ -#ifndef S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ -#define S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_GLOBAL_RANDOMIZATION_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_GLOBAL_RANDOMIZATION_HPP_ -#include "./randomize0.hpp" +#include "./minimal_standard_linear_congruential_generator.hpp" /** * @class global_randomization.hpp @@ -39,4 +39,4 @@ class GlobalRand { extern GlobalRand g_rand; //!< Global randomization -#endif // S2E_LIBRARY_MATH_GLOBAL_RANDOMIZATION_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_GLOBAL_RANDOMIZATION_HPP_ diff --git a/src/library/math/randomize0.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp similarity index 91% rename from src/library/math/randomize0.cpp rename to src/library/randomization/minimal_standard_linear_congruential_generator.cpp index df6d3bccb..96f31b63c 100644 --- a/src/library/math/randomize0.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp @@ -4,7 +4,7 @@ * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#include "randomize0.hpp" +#include "minimal_standard_linear_congruential_generator.hpp" using libra::Ran0; #include diff --git a/src/library/math/randomize0.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp similarity index 95% rename from src/library/math/randomize0.hpp rename to src/library/randomization/minimal_standard_linear_congruential_generator.hpp index 8ccda954a..021e60a7a 100644 --- a/src/library/math/randomize0.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -1,5 +1,5 @@ /** - * @file randomize0.hpp + * @file minimal_standard_linear_congruential_generator.hpp * @brief Randomization with Park and Miller's multiplicative congruential method * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ diff --git a/src/library/math/randomize1.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp similarity index 91% rename from src/library/math/randomize1.cpp rename to src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index 118235b76..7d97cbcba 100644 --- a/src/library/math/randomize1.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -4,7 +4,7 @@ * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ -#include "randomize1.hpp" +#include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" using libra::Ran1; Ran1::Ran1() : y_(0) { init_(); } diff --git a/src/library/math/randomize1.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp similarity index 92% rename from src/library/math/randomize1.hpp rename to src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index 79f7d27eb..ddc22d76f 100644 --- a/src/library/math/randomize1.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -1,5 +1,5 @@ /** - * @file randomize1.hpp + * @file minimal_standard_linear_congruential_generator_with_shuffle.hpp * @brief Randomization with Park and Miller's multiplicative congruential method combined with mixed method * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ @@ -9,7 +9,7 @@ #include // size_t -#include "randomize0.hpp" +#include "minimal_standard_linear_congruential_generator.hpp" namespace libra { diff --git a/src/library/math/normal_randomization.cpp b/src/library/randomization/normal_randomization.cpp similarity index 100% rename from src/library/math/normal_randomization.cpp rename to src/library/randomization/normal_randomization.cpp diff --git a/src/library/math/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp similarity index 89% rename from src/library/math/normal_randomization.hpp rename to src/library/randomization/normal_randomization.hpp index ab074b27f..4b65d2e09 100644 --- a/src/library/math/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -4,10 +4,10 @@ * @note Ref: NUMERICAL RECIPES in C, p.216-p.217 */ -#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ -#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ -#include "randomize1.hpp" +#include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" using libra::Ran1; namespace libra { @@ -101,6 +101,6 @@ class NormalRand { } // namespace libra -#include "normal_randomization_ifs.hpp" // inline function definisions. +#include "normal_randomization_inline_functions.hpp" -#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ diff --git a/src/library/math/normal_randomization_ifs.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp similarity index 100% rename from src/library/math/normal_randomization_ifs.hpp rename to src/library/randomization/normal_randomization_inline_functions.hpp diff --git a/src/library/math/random_walk.hpp b/src/library/randomization/random_walk.hpp similarity index 87% rename from src/library/math/random_walk.hpp rename to src/library/randomization/random_walk.hpp index a53f24ccb..884646b2a 100644 --- a/src/library/math/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -6,9 +6,9 @@ #ifndef S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ #define S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ +#include "../math/ordinary_differential_equation.hpp" +#include "../math/vector.hpp" #include "./normal_randomization.hpp" -#include "./ordinary_differential_equation.hpp" -#include "./vector.hpp" /** * @class RandomWalk @@ -40,6 +40,6 @@ class RandomWalk : public libra::ODE { libra::NormalRand nrs_[N]; //!< Random walk excitation noise }; -#include "./random_walk_tfs.hpp" // template function definisions. +#include "random_walk_template_functions.hpp" // template function definisions. #endif // S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ \ No newline at end of file diff --git a/src/library/math/random_walk_tfs.hpp b/src/library/randomization/random_walk_template_functions.hpp similarity index 94% rename from src/library/math/random_walk_tfs.hpp rename to src/library/randomization/random_walk_template_functions.hpp index d9613efb1..561a27c5b 100644 --- a/src/library/math/random_walk_tfs.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -6,7 +6,7 @@ #ifndef S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ #define S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ -#include +#include #include template diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 104a96200..5579b0508 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -6,7 +6,7 @@ #include "sample_spacecraft.hpp" #include -#include +#include #include "sample_components.hpp" From 7792c11e89cc19d0a076684850708994cf75bdda Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 08:51:27 +0100 Subject: [PATCH 0392/1086] Modify include guard --- .../minimal_standard_linear_congruential_generator.hpp | 6 +++--- ..._standard_linear_congruential_generator_with_shuffle.hpp | 6 +++--- src/library/randomization/random_walk.hpp | 6 +++--- .../randomization/random_walk_template_functions.hpp | 6 +++--- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index 021e60a7a..26ff8be54 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -4,8 +4,8 @@ * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#ifndef S2E_LIBRARY_MATH_RANDOMIZE0_HPP_ -#define S2E_LIBRARY_MATH_RANDOMIZE0_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ namespace libra { @@ -54,4 +54,4 @@ class Ran0 { } // namespace libra -#endif // S2E_LIBRARY_MATH_RANDOMIZE0_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index ddc22d76f..817c4c0f0 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -4,8 +4,8 @@ * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ -#ifndef S2E_LIBRARY_MATH_RANDOMIZE1_HPP_ -#define S2E_LIBRARY_MATH_RANDOMIZE1_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ #include // size_t @@ -61,4 +61,4 @@ class Ran1 { } // namespace libra -#endif // S2E_LIBRARY_MATH_RANDOMIZE1_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index 884646b2a..097a9ec09 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate random wark value */ -#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ -#define S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_RANDOM_WALK_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_RANDOM_WALK_HPP_ #include "../math/ordinary_differential_equation.hpp" #include "../math/vector.hpp" @@ -42,4 +42,4 @@ class RandomWalk : public libra::ODE { #include "random_walk_template_functions.hpp" // template function definisions. -#endif // S2E_LIBRARY_MATH_RANDOM_WALK_HPP_ \ No newline at end of file +#endif // S2E_LIBRARY_RANDOMIZATION_RANDOM_WALK_HPP_ \ No newline at end of file diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 561a27c5b..30cdc5269 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate random wark value (template functions) */ -#ifndef S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ -#define S2E_LIBRARY_MATH_RANDOM_WALK_TFS_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_RANDOM_WALK_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_RANDOM_WALK_TEMPLATE_FUNCTIONS_HPP_ #include #include @@ -32,4 +32,4 @@ void RandomWalk::RHS(double x, const libra::Vector& state, libra::Vector Date: Mon, 13 Feb 2023 08:55:51 +0100 Subject: [PATCH 0393/1086] Rename ifs tfs --- src/library/math/matrix.hpp | 4 ++-- .../math/{matrix_ifs.hpp => matrix_inline_functions.hpp} | 6 +++--- .../math/{matrix_tfs.hpp => matrix_template_functions.hpp} | 6 +++--- 3 files changed, 8 insertions(+), 8 deletions(-) rename src/library/math/{matrix_ifs.hpp => matrix_inline_functions.hpp} (88%) rename src/library/math/{matrix_tfs.hpp => matrix_template_functions.hpp} (96%) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index bce57182b..b48a87c31 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -253,7 +253,7 @@ Matrix rotz(const double& theta); } // namespace libra -#include "matrix_ifs.hpp" // inline function definisions. -#include "matrix_tfs.hpp" // template function definisions. +#include "matrix_inline_functions.hpp" +#include "matrix_template_functions.hpp" #endif // S2E_LIBRARY_MATH_MATRIX_HPP_ diff --git a/src/library/math/matrix_ifs.hpp b/src/library/math/matrix_inline_functions.hpp similarity index 88% rename from src/library/math/matrix_ifs.hpp rename to src/library/math/matrix_inline_functions.hpp index aa646689f..2648f07a6 100644 --- a/src/library/math/matrix_ifs.hpp +++ b/src/library/math/matrix_inline_functions.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ -#define S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ #include // for invalid_argument @@ -56,4 +56,4 @@ bool Matrix::is_valid_range_(size_t row, size_t column) { } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ diff --git a/src/library/math/matrix_tfs.hpp b/src/library/math/matrix_template_functions.hpp similarity index 96% rename from src/library/math/matrix_tfs.hpp rename to src/library/math/matrix_template_functions.hpp index 957928914..991b9e42a 100644 --- a/src/library/math/matrix_tfs.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -3,8 +3,8 @@ * @brief Matrix class to handle math matrix with template */ -#ifndef S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ -#define S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_TEMPLATE_FUNCTIONS_HPP_ #include #include // for cout @@ -192,4 +192,4 @@ Matrix rotz(const double& theta) { } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_TFS_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_TEMPLATE_FUNCTIONS_HPP_ From 9ae503a036b0e000506cf92fe147ead6af9d0c9b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:07:31 +0100 Subject: [PATCH 0394/1086] Rename ifs tfs --- src/library/math/vector.hpp | 4 ++-- .../math/{vector_ifs.hpp => vector_inline_functions.hpp} | 0 .../math/{vector_tfs.hpp => vector_template_functions.hpp} | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/library/math/{vector_ifs.hpp => vector_inline_functions.hpp} (100%) rename src/library/math/{vector_tfs.hpp => vector_template_functions.hpp} (100%) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 987146f24..40e7e738a 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -245,7 +245,7 @@ Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v); } // namespace libra -#include "vector_ifs.hpp" // inline function definisions. -#include "vector_tfs.hpp" // template function definisions. +#include "vector_inline_functions.hpp" +#include "vector_template_functions.hpp" #endif // S2E_LIBRARY_MATH_VECTOR_HPP_ diff --git a/src/library/math/vector_ifs.hpp b/src/library/math/vector_inline_functions.hpp similarity index 100% rename from src/library/math/vector_ifs.hpp rename to src/library/math/vector_inline_functions.hpp diff --git a/src/library/math/vector_tfs.hpp b/src/library/math/vector_template_functions.hpp similarity index 100% rename from src/library/math/vector_tfs.hpp rename to src/library/math/vector_template_functions.hpp From 89d26a1d34c249e4380dd6589ad334c7a000e79f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:12:29 +0100 Subject: [PATCH 0395/1086] Rename ifs tfs --- src/library/math/ordinary_differential_equation.hpp | 4 ++-- ... => ordinary_differential_equation_inline_functions.hpp} | 6 +++--- ...> ordinary_differential_equation_template_functions.hpp} | 6 +++--- src/library/math/quaternion.hpp | 2 +- .../{quaternion_ifs.hpp => quaternion_inline_functions.hpp} | 6 +++--- .../randomization/normal_randomization_inline_functions.hpp | 6 +++--- 6 files changed, 15 insertions(+), 15 deletions(-) rename src/library/math/{ordinary_differential_equation_ifs.hpp => ordinary_differential_equation_inline_functions.hpp} (74%) rename src/library/math/{ordinary_differential_equation_tfs.hpp => ordinary_differential_equation_template_functions.hpp} (83%) rename src/library/math/{quaternion_ifs.hpp => quaternion_inline_functions.hpp} (77%) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index f3e35f1a9..d25f84943 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -111,7 +111,7 @@ class ODE { } // namespace libra -#include "./ordinary_differential_equation_ifs.hpp" // inline function definisions. -#include "./ordinary_differential_equation_tfs.hpp" // template function definisions. +#include "./ordinary_differential_equation_inline_functions.hpp" +#include "./ordinary_differential_equation_template_functions.hpp" #endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ diff --git a/src/library/math/ordinary_differential_equation_ifs.hpp b/src/library/math/ordinary_differential_equation_inline_functions.hpp similarity index 74% rename from src/library/math/ordinary_differential_equation_ifs.hpp rename to src/library/math/ordinary_differential_equation_inline_functions.hpp index 60ebef3b6..c99f7c1cc 100644 --- a/src/library/math/ordinary_differential_equation_ifs.hpp +++ b/src/library/math/ordinary_differential_equation_inline_functions.hpp @@ -3,8 +3,8 @@ * @brief Class for Ordinary Difference Equation (inline functions) */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ namespace libra { @@ -43,4 +43,4 @@ libra::Vector& ODE::state() { } // namespace libra -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ diff --git a/src/library/math/ordinary_differential_equation_tfs.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp similarity index 83% rename from src/library/math/ordinary_differential_equation_tfs.hpp rename to src/library/math/ordinary_differential_equation_template_functions.hpp index 40643a218..24c5d90e1 100644 --- a/src/library/math/ordinary_differential_equation_tfs.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -2,8 +2,8 @@ * @file ordinary_differential_equation_tfs.hpp * @brief Class for Ordinary Difference Equation (template functions) */ -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ +#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ namespace libra { @@ -49,4 +49,4 @@ void ODE::setStepWidth(double new_step) { } } // namespace libra -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TFS_HPP_ +#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index bb3b6684d..79aa26106 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -207,6 +207,6 @@ Quaternion operator*(const Quaternion& lhs, const Vector<3>& rhs); Quaternion operator*(const double& lhs, const Quaternion& rhs); } // namespace libra -#include "quaternion_ifs.hpp" // inline function definisions. +#include "quaternion_inline_functions.hpp" #endif // S2E_LIBRARY_MATH_QUATERNION_HPP_ diff --git a/src/library/math/quaternion_ifs.hpp b/src/library/math/quaternion_inline_functions.hpp similarity index 77% rename from src/library/math/quaternion_ifs.hpp rename to src/library/math/quaternion_inline_functions.hpp index f026ddf70..b4b343c25 100644 --- a/src/library/math/quaternion_ifs.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -3,8 +3,8 @@ * @brief Class for Quaternion (Inline functions) */ -#ifndef S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ -#define S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ namespace libra { @@ -32,4 +32,4 @@ Quaternion::operator const Vector<4>&() const { return q_; } } // namespace libra -#endif // S2E_LIBRARY_MATH_QUATERNION_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp index fd95f7f96..85e1cf0ac 100644 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ b/src/library/randomization/normal_randomization_inline_functions.hpp @@ -3,8 +3,8 @@ * @brief Class to generate random value with normal distribution with Box-Muller method * @note Inline functions */ -#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ -#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ +#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ namespace libra { @@ -29,4 +29,4 @@ void NormalRand::set_param(double avg, double stddev, long seed) { } // namespace libra -#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_IFS_HPP_ +#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ From 3d43d94b7ab82c1b4b23a6f1b468526f4ad5478e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:12:54 +0100 Subject: [PATCH 0396/1086] Delete unused file --- .../ordinary_differential_equation_impl.hpp | 46 ------------------- 1 file changed, 46 deletions(-) delete mode 100644 src/library/math/ordinary_differential_equation_impl.hpp diff --git a/src/library/math/ordinary_differential_equation_impl.hpp b/src/library/math/ordinary_differential_equation_impl.hpp deleted file mode 100644 index 404f68e18..000000000 --- a/src/library/math/ordinary_differential_equation_impl.hpp +++ /dev/null @@ -1,46 +0,0 @@ -/*! -/** - * @file ordinary_differential_equation_impl.hpp - * @brief Class for Ordinary Difference Equation - */ - -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ - -namespace libra { - -template -ODE::ODE(double step_width) : Logger(), x_(0.0), state_(0.0), rhs_(0.0), step_width_(step_width) {} - -template -void ODE::setup(double init_x, const Vector& init_cond) { - x_ = init_x; - state_ = init_cond; -} - -template -ODE& ODE::operator++() { - RHS(x_, state_, rhs_); // Calculation of current derivative - write_log(); // Write log - - // 4th order Runge-Kutta method - Vector k1(rhs_); - k1 *= step_width_; - Vector k2(state_.dim()); - RHS(x_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); - k2 *= step_width_; - Vector k3(state_.dim()); - RHS(x_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); - k3 *= step_width_; - Vector k4(state_.dim()); - RHS(x_ + step_width_, state_ + k3, k4); - k4 *= step_width_; - - state_ += (1.0 / 6.0) * (k1 + 2.0 * (k2 + k3) + k4); // Update state vector - x_ += step_width_; // Update independent variable - return *this; -} - -} // namespace libra - -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_IMPL_HPP_ From 79c53afff58aed4cb414b752eda246acde64713c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:14:54 +0100 Subject: [PATCH 0397/1086] Rename impl --- src/library/math/matrix_vector.hpp | 2 +- ...ctor_impl.hpp => matrix_vector_template_functions.hpp} | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) rename src/library/math/{matrix_vector_impl.hpp => matrix_vector_template_functions.hpp} (92%) diff --git a/src/library/math/matrix_vector.hpp b/src/library/math/matrix_vector.hpp index 82634c07c..da0bac226 100644 --- a/src/library/math/matrix_vector.hpp +++ b/src/library/math/matrix_vector.hpp @@ -54,6 +54,6 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& } // namespace libra -#include "matrix_vector_impl.hpp" +#include "matrix_vector_template_functions.hpp" #endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_HPP_ diff --git a/src/library/math/matrix_vector_impl.hpp b/src/library/math/matrix_vector_template_functions.hpp similarity index 92% rename from src/library/math/matrix_vector_impl.hpp rename to src/library/math/matrix_vector_template_functions.hpp index 30688961b..8a41ef78c 100644 --- a/src/library/math/matrix_vector_impl.hpp +++ b/src/library/math/matrix_vector_template_functions.hpp @@ -1,10 +1,10 @@ /** - * @file matrix_vector_impl.hpp + * @file matrix_vector_template_functions.hpp * @brief Template library for Matrix-Vector calculation */ -#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ -#define S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ +#ifndef S2E_LIBRARY_MATH_MATRIX_VECTOR_TEMPLATE_FUNCTIONS_HPP_ +#define S2E_LIBRARY_MATH_MATRIX_VECTOR_TEMPLATE_FUNCTIONS_HPP_ #include // for invalid_argument. @@ -141,4 +141,4 @@ Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& } // namespace libra -#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_IMPL_HPP_ +#endif // S2E_LIBRARY_MATH_MATRIX_VECTOR_TEMPLATE_FUNCTIONS_HPP_ From 38400a227d72aba750d857e9805fb45e9ea867d1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:22:22 +0100 Subject: [PATCH 0398/1086] Fix comment --- src/library/math/matrix_inline_functions.hpp | 2 +- src/library/math/matrix_template_functions.hpp | 2 +- .../math/ordinary_differential_equation_inline_functions.hpp | 2 +- .../math/ordinary_differential_equation_template_functions.hpp | 2 +- src/library/math/quaternion_inline_functions.hpp | 2 +- src/library/math/vector_inline_functions.hpp | 2 +- src/library/math/vector_template_functions.hpp | 2 +- .../randomization/normal_randomization_inline_functions.hpp | 2 +- src/library/randomization/random_walk_template_functions.hpp | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/library/math/matrix_inline_functions.hpp b/src/library/math/matrix_inline_functions.hpp index 2648f07a6..2ce1b73d7 100644 --- a/src/library/math/matrix_inline_functions.hpp +++ b/src/library/math/matrix_inline_functions.hpp @@ -1,5 +1,5 @@ /** - * @file matrix_ifs.hpp + * @file matrix_inline_functions.hpp * @brief Matrix class to handle math matrix with template */ diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 991b9e42a..8f88e04aa 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -1,5 +1,5 @@ /** - * @file matrix_tfs.hpp + * @file matrix_template_functions.hpp * @brief Matrix class to handle math matrix with template */ diff --git a/src/library/math/ordinary_differential_equation_inline_functions.hpp b/src/library/math/ordinary_differential_equation_inline_functions.hpp index c99f7c1cc..8dca553b9 100644 --- a/src/library/math/ordinary_differential_equation_inline_functions.hpp +++ b/src/library/math/ordinary_differential_equation_inline_functions.hpp @@ -1,5 +1,5 @@ /** - * @file ordinary_differential_equation_ifs.hpp + * @file ordinary_differential_equation_inline_functions.hpp * @brief Class for Ordinary Difference Equation (inline functions) */ diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 24c5d90e1..289307537 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -1,5 +1,5 @@ /** - * @file ordinary_differential_equation_tfs.hpp + * @file ordinary_differential_equation_template_functions.hpp * @brief Class for Ordinary Difference Equation (template functions) */ #ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index b4b343c25..296c8b036 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -1,5 +1,5 @@ /** - * @file quaternion_ifs.hpp + * @file quaternion_inline_functions.hpp * @brief Class for Quaternion (Inline functions) */ diff --git a/src/library/math/vector_inline_functions.hpp b/src/library/math/vector_inline_functions.hpp index ec8b197c0..1b436b254 100644 --- a/src/library/math/vector_inline_functions.hpp +++ b/src/library/math/vector_inline_functions.hpp @@ -1,5 +1,5 @@ /** - * @file vector_ifs.hpp + * @file vector_inline_functions.hpp * @brief Class for mathematical vector (inline functions) */ diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index fe4798bed..a52b78f38 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -1,5 +1,5 @@ /** - * @file vector_tfs.hpp + * @file vector_template_functions.hpp * @brief Class for mathematical vector (template functions) */ diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp index 85e1cf0ac..1472ed37b 100644 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ b/src/library/randomization/normal_randomization_inline_functions.hpp @@ -1,5 +1,5 @@ /** - * @file normal_randomization_ifs.hpp + * @file normal_randomization_inline_functions.hpp * @brief Class to generate random value with normal distribution with Box-Muller method * @note Inline functions */ diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 30cdc5269..15c761d14 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -1,5 +1,5 @@ /** - * @file random_walk_tfs.hpp + * @file random_walk_template_functions.hpp * @brief Class to calculate random wark value (template functions) */ From 876474c71b2a8bf005aba53be28671df1a1e2ca6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 10:38:32 +0100 Subject: [PATCH 0399/1086] Fix format --- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/magnetorquer.hpp | 4 +-- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- src/components/base/sensor.hpp | 2 +- .../ideal_components/force_generator.hpp | 2 +- .../ideal_components/torque_generator.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/library/external/igrf/igrf.cpp | 32 +++++++++---------- 12 files changed, 28 insertions(+), 28 deletions(-) diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 708a704fd..66455c54b 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -10,8 +10,8 @@ #include #include #include -#include #include +#include #include "../base/component.hpp" diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index ceb42e337..3d4efcc1f 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -6,9 +6,9 @@ #include "magnetorquer.hpp" #include -#include #include #include +#include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index af2404c7d..d02e291f6 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -9,10 +9,10 @@ #include #include #include -#include #include -#include #include +#include +#include #include "../base/component.hpp" diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index cad6af5c7..7f0f5afd6 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -8,8 +8,8 @@ #include #include #include -#include #include +#include #include using namespace std; diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index 6b87781f8..f461f3b1a 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -9,9 +9,9 @@ #include #include #include -#include #include #include +#include #include "../base/component.hpp" diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index 9f2712198..a38a764f4 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -7,9 +7,9 @@ #define S2E_COMPONENTS_BASE_SENSOR_HPP_ #include +#include #include #include -#include /** * @class SensorBase diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index b6473e190..2689ec1ee 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -9,8 +9,8 @@ #include #include #include -#include #include +#include /* * @class ForceGenerator diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index d5f1fa152..a6be77b78 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -9,8 +9,8 @@ #include #include #include -#include #include +#include /* * @class TorqueGenerator diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 7c3bb5064..6eded5ca1 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -8,9 +8,9 @@ #include #include -#include #include #include +#include #include #include "../base/component.hpp" diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 31988e619..d7853ff9d 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -6,10 +6,10 @@ #include "atmosphere.hpp" #include +#include #include #include #include -#include using libra::NormalRand; using libra::Vector; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 43f1d0a2f..62de695be 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -8,9 +8,9 @@ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ #include +#include #include #include -#include #include #include diff --git a/src/library/external/igrf/igrf.cpp b/src/library/external/igrf/igrf.cpp index 0b926088a..0d59d329d 100644 --- a/src/library/external/igrf/igrf.cpp +++ b/src/library/external/igrf/igrf.cpp @@ -292,17 +292,17 @@ void gigrf(int gen, double year) { int i, n, m, l, k, ncol, nlin; double y1, y2, yr1 = 0.0, yr2 = 0.0; double dmy[3], cb[MxELM], cv[MxELM]; - //係数表指定 - // char path[]="igrf10.coef"; - // char file[]="igrf10.coef"; - // char path[] = "igrf11.coef"; - // char file[] = "igrf11.coef"; - // char path[] = "src/library/external/igrf/igrf11.coef"; - // char file[] = "src/library/external/igrf/igrf11.coef"; - // char path[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; - // char file[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; - // char path[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 - // char file[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 + // 係数表指定 + // char path[]="igrf10.coef"; + // char file[]="igrf10.coef"; + // char path[] = "igrf11.coef"; + // char file[] = "igrf11.coef"; + // char path[] = "src/library/external/igrf/igrf11.coef"; + // char file[] = "src/library/external/igrf/igrf11.coef"; + // char path[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; + // char file[] = "../SatAttSim/src/library/external/igrf/igrf12.coef"; + // char path[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 + // char file[] = "../../SatAttSim/src/library/external/igrf/igrf13.coef"; //from 2020 char file[256]; @@ -417,8 +417,8 @@ void gigrf(int gen, double year) { } } maxod = k; - //ジオイドに関わる定数?? field(double are, double aflat, double ara, int - // maxoda) + // ジオイドに関わる定数?? field(double are, double aflat, double ara, int + // maxoda) field(6378.137, 298.25722, 6371.2, maxod); tcoef(vgh, vght, tzero, 0, dmy); tyear(year); @@ -429,7 +429,7 @@ void igrfc(double fido, double fkeido, double hght, double *tf) { mfldg(fido, fkeido, hght / 1000., &fx, &fy, &fz, tf); } -//地磁気要素(地心表現)をECI座標へ +// 地磁気要素(地心表現)をECI座標へ int TransMagaxisToECI(const double *mag, double *pos, double lonrad, double thetarad, double gmst) { RotationY(mag, pos, 180 * DEG2RAD - thetarad); RotationZ(pos, pos, -lonrad); @@ -450,9 +450,9 @@ void IgrfCalc(double decyear, double latrad, double lonrad, double alt, double s gigrf(13, decyear); first_flg = false; } - tyear(decyear); //実行年の設定 + tyear(decyear); // 実行年の設定 igrfc(latrad * RAD2DEG, lonrad * RAD2DEG, alt, - &f); //実行位置の設定&Executeはこの中に含む + &f); // 実行位置の設定&Executeはこの中に含む mag[0] = x; // x,y,zはigrf.cppグローバル変数 mag[1] = y; From 377a8fd87d80b57ad9559d12ff4d25ded919cec1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 15:35:50 +0100 Subject: [PATCH 0400/1086] Delete old CI --- .gitlab-ci.yml | 11 ----------- scripts/CI/build_on_vs2019.bat | 27 --------------------------- 2 files changed, 38 deletions(-) delete mode 100644 .gitlab-ci.yml delete mode 100644 scripts/CI/build_on_vs2019.bat diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml deleted file mode 100644 index 1a0495257..000000000 --- a/.gitlab-ci.yml +++ /dev/null @@ -1,11 +0,0 @@ -stages: - - build -variables: - GIT_STRATEGY: clone - GIT_SUBMODULE_STRATEGY: recursive -build_on_vs2019: - stage: build - script: - - echo %CD% - - cd ./scripts/CI - - ./build_on_vs2019.bat diff --git a/scripts/CI/build_on_vs2019.bat b/scripts/CI/build_on_vs2019.bat deleted file mode 100644 index fcbd62f75..000000000 --- a/scripts/CI/build_on_vs2019.bat +++ /dev/null @@ -1,27 +0,0 @@ -rem @ECHO OFF // CI猩₷悤ɈURgAEg - -rem R[hutf-8 -chcp 65001 - -rem JgfBNgob`̏ꏊɂ -cd /d %~dp0 - -rem s2e root dir̂P -cd ..\..\..\ -echo ### Copy S2E to temp dir -if exist ".\s2e_core_oss_temp" ( - rmdir /s /q ".\s2e_core_oss_temp" -) -xcopy /i /e /q ".\s2e_core_oss" ".\s2e_core_oss_temp" -echo ### Copy S2E build env -xcopy /i /e /q "C:\GitLab-Runner\temlate\S2E" ".\s2e_core_oss\S2E\" -echo ### Move S2E to S2E env -move ".\s2e_core_oss_temp" ".\s2e_core_oss\S2E" -cd ".\s2e_core_oss\S2E\" -rename "s2e_core_oss_temp" "s2e_core_oss" - -echo ### Build with VS2019 -cd ".\s2e_core_oss\" -call "C:\Program Files (x86)\Microsoft Visual Studio\2019\Community\VC\Auxiliary\Build\vcvars32.bat" -cmake -G "Visual Studio 16 2019" -A Win32 -DCMAKE_CONFIGURATION_TYPES:STRING="Debug" -cmake --build . From 6eacd70eff7344802a7a2aa4c7fc70d24197c9f2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Feb 2023 16:33:48 +0100 Subject: [PATCH 0401/1086] Add argument read function --- scripts/Plot/common.py | 6 ++++++ scripts/Plot/plot_body_frame_info.py | 7 +++---- scripts/Plot/plot_disturbance_force.py | 9 ++++----- scripts/Plot/plot_disturbance_torque.py | 10 +++++----- scripts/Plot/plot_gs_visibility.py | 7 +++---- scripts/Plot/plot_orbit_eci.py | 7 +++---- scripts/Plot/plot_satellite_orbit_on_miller.py | 7 +++---- 7 files changed, 27 insertions(+), 26 deletions(-) diff --git a/scripts/Plot/common.py b/scripts/Plot/common.py index b1cb18b48..c5a4a4bd3 100644 --- a/scripts/Plot/common.py +++ b/scripts/Plot/common.py @@ -2,6 +2,7 @@ import numpy as np from numpy.linalg import norm import pandas +import argparse def find_latest_log_tag(logs_dir): dlist = sorted(os.listdir(logs_dir)) @@ -33,3 +34,8 @@ def read_scalar_from_csv(read_file_name, header_name): csv_data = pandas.read_csv(read_file_name, sep=',', usecols=[header_name]) vector = np.array([csv_data[header_name].to_numpy()]) return vector + +def add_log_file_arguments(aparser): + aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/sample/logs"', default='../../data/sample/logs') + aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') + return aparser diff --git a/scripts/Plot/plot_body_frame_info.py b/scripts/Plot/plot_body_frame_info.py index e4bf21505..cd5186a8f 100644 --- a/scripts/Plot/plot_body_frame_info.py +++ b/scripts/Plot/plot_body_frame_info.py @@ -12,18 +12,17 @@ import matplotlib.pyplot as plt # local function from common import find_latest_log_tag +from common import add_log_file_arguments from common import normalize_csv_read_vector from common import read_3d_vector_from_csv # arguments import argparse +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() # diff --git a/scripts/Plot/plot_disturbance_force.py b/scripts/Plot/plot_disturbance_force.py index f406ad7b0..7878ac55f 100644 --- a/scripts/Plot/plot_disturbance_force.py +++ b/scripts/Plot/plot_disturbance_force.py @@ -11,17 +11,16 @@ import matplotlib.pyplot as plt # local function from common import find_latest_log_tag +from common import add_log_file_arguments from common import read_3d_vector_from_csv from common import read_scalar_from_csv # arguments import argparse +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() # @@ -46,7 +45,7 @@ # Data read and edit # # Read S2E CSV -time = read_scalar_from_csv(read_file_name, 'time[s]') +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') srp_force_b = read_3d_vector_from_csv(read_file_name, 'srp_force_b', 'N') airdrag_force_b = read_3d_vector_from_csv(read_file_name, 'air_drag_force_b', 'N') diff --git a/scripts/Plot/plot_disturbance_torque.py b/scripts/Plot/plot_disturbance_torque.py index dc9a923a0..b83379fb3 100644 --- a/scripts/Plot/plot_disturbance_torque.py +++ b/scripts/Plot/plot_disturbance_torque.py @@ -11,19 +11,19 @@ import matplotlib.pyplot as plt # local function from common import find_latest_log_tag +from common import add_log_file_arguments from common import read_3d_vector_from_csv from common import read_scalar_from_csv # arguments import argparse +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() + # # Read Arguments # @@ -46,7 +46,7 @@ # Data read and edit # # Read S2E CSV -time = read_scalar_from_csv(read_file_name, 'time[s]') +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') total_torque_b = read_3d_vector_from_csv(read_file_name, 'spacecraft_torque_b', 'Nm') gg_torque_b = read_3d_vector_from_csv(read_file_name, 'gravity_gradient_torque_b', 'Nm') diff --git a/scripts/Plot/plot_gs_visibility.py b/scripts/Plot/plot_gs_visibility.py index f9a895bdc..a02f786f4 100644 --- a/scripts/Plot/plot_gs_visibility.py +++ b/scripts/Plot/plot_gs_visibility.py @@ -17,16 +17,15 @@ # local function from make_miller_projection_map import make_miller_projection_map from common import find_latest_log_tag +from common import add_log_file_arguments from common import read_scalar_from_csv # arguments import argparse +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/sample/logs"', default='../../data/sample/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() # diff --git a/scripts/Plot/plot_orbit_eci.py b/scripts/Plot/plot_orbit_eci.py index 63d89e59b..992a811a3 100644 --- a/scripts/Plot/plot_orbit_eci.py +++ b/scripts/Plot/plot_orbit_eci.py @@ -17,6 +17,7 @@ import pandas # local function from common import find_latest_log_tag +from common import add_log_file_arguments from common import normalize_csv_read_vector from common import read_3d_vector_from_csv from common import read_scalar_from_csv @@ -25,13 +26,11 @@ # math from numpy.linalg import norm +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--is-animation', type=bool, help='True: generate animation, False: generate plot', default=False) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() # diff --git a/scripts/Plot/plot_satellite_orbit_on_miller.py b/scripts/Plot/plot_satellite_orbit_on_miller.py index 8933d125b..b51035b67 100644 --- a/scripts/Plot/plot_satellite_orbit_on_miller.py +++ b/scripts/Plot/plot_satellite_orbit_on_miller.py @@ -12,16 +12,15 @@ # local function from make_miller_projection_map import make_miller_projection_map from common import find_latest_log_tag +from common import add_log_file_arguments from common import read_scalar_from_csv # arguments import argparse +# Arguments aparser = argparse.ArgumentParser() - -aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/SampleSat/logs"', default='../../data/SampleSat/logs') -aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') +aparser = add_log_file_arguments(aparser) aparser.add_argument('--no-gui', action='store_true') - args = aparser.parse_args() # From 1d7e8e99ca504bb2e95204c8c04655ff7cfb090b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 14 Feb 2023 13:28:40 +0100 Subject: [PATCH 0402/1086] Add sample STL file --- scripts/Plot/data/sample_6u_cubesat.stl | Bin 0 -> 3484 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 scripts/Plot/data/sample_6u_cubesat.stl diff --git a/scripts/Plot/data/sample_6u_cubesat.stl b/scripts/Plot/data/sample_6u_cubesat.stl new file mode 100644 index 0000000000000000000000000000000000000000..f6c725fd3b84ad45f95e82f9c1f2954900eb41cc GIT binary patch literal 3484 zcmbW3!D>@s5QXnXd;vFZBrjk=gUhraiZ0yd4H{Q!CAbhl$!jRSMO_JL=uR;D5I%tT z2KE2upEH^N-Xx|5(mULlGiT13DedF8ug~UhW~Za)^Rt(uhc9NYPG|GG&)>dJF28pbh6wpXC&iok!m;vR^yLz%iWuK`zaOD0Iw=NGuaJno%Jezl1GyDJ#=ZqD z<&6$Fo_^WIL0>w6=Gk?Ai3PRU2QHGuAD)gN_NlI}o;(l&9b{A`-!>do`6y3iJwa#( zLept@yXr+&{wUTy7Ix`Al~ws9u>%mAHaMg_GTztpD8>;w4>-66yaKI#SX|x}cPrx0 zm`GJ*h|!TJy`oVHliJnQdALQKZv^FS*e zATmevEt3_+m3x4Q4D+imaYi)mHhtYIyGjsS_hB5q57UujTrkD?O7c_<-{Bl`x6xrY z1)J3RB&JreG}%-QLK)E7+Q6#@A$IX;|2PfbevUqRD*{I^lG=#NgiE;#51)Eh%D4`z zavg@Qwe@G*uKIE%ii5lBrqdhe3BlF|eG5lIsG6rwqTf{8x$h(PU+dAZ3n6#48|ntP ztEsrLEjs#$zFJKMI`*;BY$#NQ7#D<)Bg3gOM<1;XHh-g*>gB$PgFD_#)xSi`fPl}Z zif!6d14MFEzFmVuXr>As*{fy}&7L*M*Xmi$l(=zM=mDbHM_+l}V7XoUOHg{~zYIB= z(J`$!>TUHVvE9gB?djhL_sTTMtE!rxaFp4P)wdrXh7bqn24Q>0-Q*8^x)O^ILpX~aPbe3dYCD3hMb))AqA$~`Q`h|kjcCT< literal 0 HcmV?d00001 From b5a7cc55d4a55108c903ee94352f84374636468b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 14 Feb 2023 13:29:01 +0100 Subject: [PATCH 0403/1086] Add STL in graph --- scripts/Plot/common.py | 11 +++++++++++ scripts/Plot/plot_body_frame_info.py | 3 +++ 2 files changed, 14 insertions(+) diff --git a/scripts/Plot/common.py b/scripts/Plot/common.py index c5a4a4bd3..ff373e5fd 100644 --- a/scripts/Plot/common.py +++ b/scripts/Plot/common.py @@ -4,6 +4,10 @@ import pandas import argparse +# 3D model +from stl import mesh +import mpl_toolkits + def find_latest_log_tag(logs_dir): dlist = sorted(os.listdir(logs_dir)) latest_log = None @@ -39,3 +43,10 @@ def add_log_file_arguments(aparser): aparser.add_argument('--logs-dir', type=str, help='logs directory like "../../data/sample/logs"', default='../../data/sample/logs') aparser.add_argument('--file-tag', type=str, help='log file tag like 220627_142946') return aparser + +def add_stl_model(plot_axis, file_name, alpha=0.7, color='orange'): + sc_mesh = mesh.Mesh.from_file(file_name) + sc_size_max = np.max([sc_mesh.x.max(),sc_mesh.y.max(),sc_mesh.z.max()]) + scale = 0.7 / sc_size_max + plot_axis.add_collection3d(mpl_toolkits.mplot3d.art3d.Poly3DCollection(sc_mesh.vectors * scale, alpha=alpha, color=color)) + diff --git a/scripts/Plot/plot_body_frame_info.py b/scripts/Plot/plot_body_frame_info.py index cd5186a8f..e4d6f6236 100644 --- a/scripts/Plot/plot_body_frame_info.py +++ b/scripts/Plot/plot_body_frame_info.py @@ -15,6 +15,7 @@ from common import add_log_file_arguments from common import normalize_csv_read_vector from common import read_3d_vector_from_csv +from common import add_stl_model # arguments import argparse @@ -74,6 +75,8 @@ ax.quiver(0, 0, 0, 0.5, 0, 0, color='r', label="X") # X-axis ax.quiver(0, 0, 0, 0, 0.5, 0, color='g', label="Y") # Y-axis ax.quiver(0, 0, 0, 0, 0, 0.5, color='b', label="Z") # Z-axis +# Add Spacecraft mesh +add_stl_model(ax, "./data/sample_6u_cubesat.stl") # Plot Celestial bodies ax.plot(sun_direction_b[0], sun_direction_b[1], sun_direction_b[2], marker="o", c="red", label="Sun") From 5a4cb8ec0a53ecc5daefe9396ce7305ac41e4a0b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 14 Feb 2023 14:08:20 +0100 Subject: [PATCH 0404/1086] Update Pipfiles --- scripts/Plot/Pipfile | 1 + scripts/Plot/Pipfile.lock | 18 +++++++++++++++++- 2 files changed, 18 insertions(+), 1 deletion(-) diff --git a/scripts/Plot/Pipfile b/scripts/Plot/Pipfile index 0bbd98a4d..338b48c66 100644 --- a/scripts/Plot/Pipfile +++ b/scripts/Plot/Pipfile @@ -8,6 +8,7 @@ basemap = "==1.3.6" matplotlib = "==3.6.3" numpy = "==1.23.5" pandas = "==1.5.3" +numpy-stl = "==3.0.0" [dev-packages] diff --git a/scripts/Plot/Pipfile.lock b/scripts/Plot/Pipfile.lock index 0369aa775..422476ce5 100644 --- a/scripts/Plot/Pipfile.lock +++ b/scripts/Plot/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "6104edf34a92d0aae80a7fc620e18728bb34d764d1d93ba55c3f91dc1a13eb4b" + "sha256": "f8f8f0802c1f1c0284a258345b59a5d36c0fbdf2df4bd2d8d48a425a0b07a423" }, "pipfile-spec": 6, "requires": { @@ -303,6 +303,14 @@ "index": "pypi", "version": "==1.23.5" }, + "numpy-stl": { + "hashes": [ + "sha256:44d56dec3b409b73f7126089ece859d0213d302e39c2375496e64f6dc574347c", + "sha256:578b78eacb0529ac9aba2f17dcc363d58c7c3c5708710c18f8c1e9965f2e81ac" + ], + "index": "pypi", + "version": "==3.0.0" + }, "packaging": { "hashes": [ "sha256:714ac14496c3e68c99c29b00845f7a2b85f3bb6f1078fd9f72fd20f0570002b2", @@ -492,6 +500,14 @@ "markers": "python_version >= '2.7' and python_version not in '3.0, 3.1, 3.2, 3.3'", "version": "==2.8.2" }, + "python-utils": { + "hashes": [ + "sha256:68198854fc276bc4b2403b261703c218e01ef564dcb072a7096ed9ea7aa5130c", + "sha256:8bfefc3430f1c48408fa0e5958eee51d39840a5a987c2181a579e99ab6fe5ca6" + ], + "markers": "python_version >= '3.7'", + "version": "==3.5.2" + }, "pytz": { "hashes": [ "sha256:01a0681c4b9684a28304615eba55d1ab31ae00bf68ec157ec3708a8182dbbcd0", From a3007bd55e65ac1207b02f1a4e7e3527c6083400 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 14 Feb 2023 19:18:12 +0100 Subject: [PATCH 0405/1086] Fix legend --- scripts/Plot/plot_body_frame_info.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/scripts/Plot/plot_body_frame_info.py b/scripts/Plot/plot_body_frame_info.py index e4d6f6236..7f4d72417 100644 --- a/scripts/Plot/plot_body_frame_info.py +++ b/scripts/Plot/plot_body_frame_info.py @@ -71,12 +71,12 @@ ax = plt.axes(projection="3d") # Plot Spacecraft -ax.plot(0,0,0, marker="*", c="black", markersize=10, label="Sat") ax.quiver(0, 0, 0, 0.5, 0, 0, color='r', label="X") # X-axis ax.quiver(0, 0, 0, 0, 0.5, 0, color='g', label="Y") # Y-axis ax.quiver(0, 0, 0, 0, 0, 0.5, color='b', label="Z") # Z-axis -# Add Spacecraft mesh -add_stl_model(ax, "./data/sample_6u_cubesat.stl") + +# ax.plot(0,0,0, marker="*", c="black", markersize=10, label="Sat") # Please use this when you don't have mesh data +add_stl_model(ax, "./data/sample_6u_cubesat.stl") # Add Spacecraft mesh # Plot Celestial bodies ax.plot(sun_direction_b[0], sun_direction_b[1], sun_direction_b[2], marker="o", c="red", label="Sun") From ba6b4a80c98ce91162f42fc61909a3433be6f905 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 10:12:10 +0100 Subject: [PATCH 0406/1086] Remove using --- src/disturbances/disturbance.hpp | 25 ++++++++++++------------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 67f14e8b9..56f905a90 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -7,7 +7,6 @@ #define S2E_DISTURBANCES_DISTURBANCE_HPP_ #include "../library/math/vector.hpp" -using libra::Vector; /** * @class Disturbance @@ -20,40 +19,40 @@ class Disturbance { * @brief Constructor */ Disturbance() { - force_b_ = Vector<3>(0); - torque_b_ = Vector<3>(0); - acceleration_b_ = Vector<3>(0); - acceleration_b_ = Vector<3>(0); + force_b_ = libra::Vector<3>(0); + torque_b_ = libra::Vector<3>(0); + acceleration_b_ = libra::Vector<3>(0); + acceleration_b_ = libra::Vector<3>(0); } /** * @fn GetTorque * @brief Return the disturbance torque in the body frame [Nm] */ - virtual inline Vector<3> GetTorque() { return torque_b_; } + virtual inline libra::Vector<3> GetTorque() { return torque_b_; } /** * @fn GetTorque * @brief Return the disturbance force in the body frame [N] */ - virtual inline Vector<3> GetForce() { return force_b_; } + virtual inline libra::Vector<3> GetForce() { return force_b_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the body frame [m/s2] */ - virtual inline Vector<3> GetAccelerationB() { return acceleration_b_; } + virtual inline libra::Vector<3> GetAccelerationB() { return acceleration_b_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the inertial frame [m/s2] */ - virtual inline Vector<3> GetAccelerationI() { return acceleration_i_; } + virtual inline libra::Vector<3> GetAccelerationI() { return acceleration_i_; } bool IsCalcEnabled = true; //!< Flag to calculate the disturbance protected: - Vector<3> force_b_; //!< Disturbance force in the body frame [N] - Vector<3> torque_b_; //!< Disturbance torque in the body frame [Nm] - Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] - Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] + libra::Vector<3> force_b_; //!< Disturbance force in the body frame [N] + libra::Vector<3> torque_b_; //!< Disturbance torque in the body frame [Nm] + libra::Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] + libra::Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] }; #endif // S2E_DISTURBANCES_DISTURBANCE_HPP_ From 3cc47c17332a041c35d22ba97dcc1740934c5b4c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 10:12:50 +0100 Subject: [PATCH 0407/1086] User 0.0 instead of 0 --- src/disturbances/disturbance.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 56f905a90..024377d2b 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -19,10 +19,10 @@ class Disturbance { * @brief Constructor */ Disturbance() { - force_b_ = libra::Vector<3>(0); - torque_b_ = libra::Vector<3>(0); - acceleration_b_ = libra::Vector<3>(0); - acceleration_b_ = libra::Vector<3>(0); + force_b_ = libra::Vector<3>(0.0); + torque_b_ = libra::Vector<3>(0.0); + acceleration_b_ = libra::Vector<3>(0.0); + acceleration_b_ = libra::Vector<3>(0.0); } /** From 8305d4ec3f03d877a2df63f8e80d53a104062a93 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:28:21 +0100 Subject: [PATCH 0408/1086] Move IsCalcEnabled to private --- src/disturbances/acceleration_disturbance.hpp | 8 +++++- src/disturbances/air_drag.cpp | 5 ++-- src/disturbances/air_drag.hpp | 4 ++- src/disturbances/disturbance.hpp | 6 ++--- src/disturbances/geopotential.cpp | 3 ++- src/disturbances/geopotential.hpp | 3 ++- src/disturbances/gravity_gradient.cpp | 6 +++-- src/disturbances/gravity_gradient.hpp | 6 +++-- src/disturbances/initialize_disturbances.cpp | 27 +++++++++---------- src/disturbances/magnetic_disturbance.cpp | 3 ++- src/disturbances/magnetic_disturbance.hpp | 3 ++- src/disturbances/simple_disturbance.hpp | 9 ++++++- .../solar_radiation_pressure_disturbance.cpp | 3 ++- .../solar_radiation_pressure_disturbance.hpp | 3 ++- src/disturbances/surface_force.cpp | 3 ++- src/disturbances/surface_force.hpp | 3 ++- src/disturbances/third_body_gravity.cpp | 5 +++- src/disturbances/third_body_gravity.hpp | 3 ++- 18 files changed, 67 insertions(+), 36 deletions(-) diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index fd49a3551..dd3b12a64 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -16,6 +16,12 @@ */ class AccelerationDisturbance : public Disturbance, public ILoggable { public: + /** + * @fn AccelerationDisturbance + * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag + */ + AccelerationDisturbance(const bool is_calc_enabled = true) : Disturbance(is_calc_enabled) {} /** * @fn ~AccelerationDisturbance * @brief Destructor @@ -27,7 +33,7 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { * @brief Update calculated disturbance when the calculation flag is true */ virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { - if (IsCalcEnabled) { + if (is_calc_enabled_) { Update(local_env, dynamics); } else { acceleration_b_ *= 0; diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index ae46586fe..79eddd7d1 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -15,8 +15,9 @@ using namespace std; using namespace libra; -AirDrag::AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular) - : SurfaceForce(surfaces, cg_b) { +AirDrag::AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, + const bool is_calc_enabled) + : SurfaceForce(surfaces, cg_b, is_calc_enabled) { int num = surfaces_.size(); Ct_.assign(num, 1.0); Cn_.assign(num, 0.0); diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 572d59e30..3762a1daa 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -27,8 +27,10 @@ class AirDrag : public SurfaceForce { /** * @fn AirDrag * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular); + AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, + const bool is_calc_enabled = true); /** * @fn Update diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 024377d2b..ec1f684c7 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -17,8 +17,9 @@ class Disturbance { /** * @fn Disturbance * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - Disturbance() { + Disturbance(const bool is_calc_enabled = true) : is_calc_enabled_(is_calc_enabled) { force_b_ = libra::Vector<3>(0.0); torque_b_ = libra::Vector<3>(0.0); acceleration_b_ = libra::Vector<3>(0.0); @@ -46,9 +47,8 @@ class Disturbance { */ virtual inline libra::Vector<3> GetAccelerationI() { return acceleration_i_; } - bool IsCalcEnabled = true; //!< Flag to calculate the disturbance - protected: + bool is_calc_enabled_; //!< Flag to calculate the disturbance libra::Vector<3> force_b_; //!< Disturbance force in the body frame [N] libra::Vector<3> torque_b_; //!< Disturbance torque in the body frame [Nm] libra::Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 6e904a45a..c94227550 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -17,7 +17,8 @@ using namespace std; -GeoPotential::GeoPotential(const int degree, const string file_path) : degree_(degree) { +GeoPotential::GeoPotential(const int degree, const string file_path, const bool is_calc_enabled) + : AccelerationDisturbance(is_calc_enabled), degree_(degree) { // Initialize acc_ecef_ = Vector<3>(0); debug_pos_ecef_ = Vector<3>(0); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index f934350df..e29a62ea9 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -26,8 +26,9 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn GeoPotential * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - GeoPotential(const int degree, const std::string file_path); + GeoPotential(const int degree, const std::string file_path, const bool is_calc_enabled = true); /** * @fn Update diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 23668b736..a19fb85b1 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -14,9 +14,11 @@ using namespace std; -GravityGradient::GravityGradient() : GravityGradient(environment::earth_gravitational_constant_m3_s2) {} +GravityGradient::GravityGradient(const bool is_calc_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calc_enabled) {} -GravityGradient::GravityGradient(const double mu_m3_s2) : mu_m3_s2_(mu_m3_s2) { fill_up(torque_b_, 0.0); } +GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), mu_m3_s2_(mu_m3_s2) { + fill_up(torque_b_, 0.0); +} void GravityGradient::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { CalcTorque(local_env.GetCelesInfo().GetCenterBodyPosFromSC_b(), diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 2bfacddd5..5b9a9e03a 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -26,15 +26,17 @@ class GravityGradient : public SimpleDisturbance { /** * @fn GeoPotential * @brief Default Constructor + * @param [in] is_calc_enabled: Calculation flag * @note mu is automatically set as earth's gravitational constant */ - GravityGradient(); + GravityGradient(const bool is_calc_enabled = true); /** * @fn GeoPotential * @brief Constructor * @param [in] mu_m3_s2: Gravitational constant [m3/s2] + * @param [in] is_calc_enabled: Calculation flag */ - GravityGradient(const double mu_m3_s2); + GravityGradient(const double mu_m3_s2, const bool is_calc_enabled = true); /** * @fn Update diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index b658e98de..177428824 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -22,8 +22,7 @@ AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, bool calcen = conf.ReadEnable(section, CALC_LABEL); bool logen = conf.ReadEnable(section, LOG_LABEL); - AirDrag airdrag(surfaces, cg_b, t_w, t_m, molecular); - airdrag.IsCalcEnabled = calcen; + AirDrag airdrag(surfaces, cg_b, t_w, t_m, molecular, calcen); airdrag.IsLogEnabled = logen; return airdrag; @@ -36,8 +35,7 @@ SolarRadiation InitSRDist(std::string ini_path, const std::vector& surf bool calcen = conf.ReadEnable(section, CALC_LABEL); bool logen = conf.ReadEnable(section, LOG_LABEL); - SolarRadiation srdist(surfaces, cg_b); - srdist.IsCalcEnabled = calcen; + SolarRadiation srdist(surfaces, cg_b, calcen); srdist.IsLogEnabled = logen; return srdist; @@ -47,8 +45,8 @@ GravityGradient InitGravityGradient(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "GRAVITY_GRADIENT"; - GravityGradient ggdist; - ggdist.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + bool calcen = conf.ReadEnable(section, CALC_LABEL); + GravityGradient ggdist(calcen); ggdist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return ggdist; @@ -58,8 +56,8 @@ GravityGradient InitGravityGradient(std::string ini_path, const double mu_m3_s2) auto conf = IniAccess(ini_path); const char* section = "GRAVITY_GRADIENT"; - GravityGradient ggdist(mu_m3_s2); - ggdist.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + bool calcen = conf.ReadEnable(section, CALC_LABEL); + GravityGradient ggdist(mu_m3_s2, calcen); ggdist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return ggdist; @@ -69,8 +67,8 @@ MagDisturbance InitMagDisturbance(std::string ini_path, const RMMParams& rmm_par auto conf = IniAccess(ini_path); const char* section = "MAGNETIC_DISTURBANCE"; - MagDisturbance mag_dist(rmm_params); - mag_dist.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + bool calcen = conf.ReadEnable(section, CALC_LABEL); + MagDisturbance mag_dist(rmm_params, calcen); mag_dist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return mag_dist; @@ -82,8 +80,9 @@ GeoPotential InitGeoPotential(std::string ini_path) { int degree = conf.ReadInt(section, "degree"); std::string file_path = conf.ReadString(section, "coefficients_file_path"); - GeoPotential geop(degree, file_path); - geop.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + bool calcen = conf.ReadEnable(section, CALC_LABEL); + + GeoPotential geop(degree, file_path, calcen); geop.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return geop; @@ -126,8 +125,8 @@ ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path } } - ThirdBodyGravity thirdbodyg(third_body_list); - thirdbodyg.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + bool calcen = conf.ReadEnable(section, CALC_LABEL); + ThirdBodyGravity thirdbodyg(third_body_list, calcen); thirdbodyg.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return thirdbodyg; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 5672e8490..291ffce1c 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -15,7 +15,8 @@ using libra::NormalRand; using namespace std; -MagDisturbance::MagDisturbance(const RMMParams& rmm_params) : rmm_params_(rmm_params) { +MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calc_enabled) + : SimpleDisturbance(is_calc_enabled), rmm_params_(rmm_params) { for (int i = 0; i < 3; ++i) { torque_b_[i] = 0; } diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 2ad262103..62d77c7c8 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -24,8 +24,9 @@ class MagDisturbance : public SimpleDisturbance { /** * @fn MagDisturbance * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - MagDisturbance(const RMMParams& rmm_params); + MagDisturbance(const RMMParams& rmm_params, const bool is_calc_enabled = true); /** * @fn CalcRMM diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index d541b4fe2..806a162d6 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -18,6 +18,13 @@ */ class SimpleDisturbance : public Disturbance, public ILoggable { public: + /** + * @fn SimpleDisturbance + * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag + */ + SimpleDisturbance(const bool is_calc_enabled = true) : Disturbance(is_calc_enabled) {} + /** * @fn ~SimpleDisturbance * @brief Destructor @@ -29,7 +36,7 @@ class SimpleDisturbance : public Disturbance, public ILoggable { * @brief Update calculated disturbance when the calculation flag is true */ virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { - if (IsCalcEnabled) { + if (is_calc_enabled_) { Update(local_env, dynamics); } else { force_b_ *= 0; diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index fd3fb08bd..86f12bcd3 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,7 +9,8 @@ #include "../interface/log_output/log_utility.hpp" -SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b) : SurfaceForce(surfaces, cg_b) {} +SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled) + : SurfaceForce(surfaces, cg_b, is_calc_enabled) {} void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index aa7a8d9dd..20a3e4202 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -23,8 +23,9 @@ class SolarRadiation : public SurfaceForce { /** * @fn SolarRadiation * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - SolarRadiation(const vector& surfaces, const Vector<3>& cg_b); + SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled = true); /** * @fn Update diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index e07c731c0..38fbd97f5 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -11,7 +11,8 @@ using libra::Vector; using namespace libra; -SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b) : surfaces_(surfaces), cg_b_(cg_b) { +SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled) + : SimpleDisturbance(is_calc_enabled), surfaces_(surfaces), cg_b_(cg_b) { force_b_ = Vector<3>(0); torque_b_ = Vector<3>(0); diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 0cba65d36..c53321cdb 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -26,8 +26,9 @@ class SurfaceForce : public SimpleDisturbance { /** * @fn SurfaceForce * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - SurfaceForce(const vector& surfaces, const Vector<3>& cg_b); + SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled = true); /** * @fn ~SurfaceForce * @brief Destructor diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 655c1cff2..742c3b89a 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -5,7 +5,10 @@ #include "third_body_gravity.hpp" -ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list) : third_body_list_(third_body_list) { acceleration_i_ *= 0; } +ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calc_enabled) + : AccelerationDisturbance(is_calc_enabled), third_body_list_(third_body_list) { + acceleration_i_ *= 0; +} ThirdBodyGravity::~ThirdBodyGravity() {} diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 58ce78129..05ffb635b 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -23,8 +23,9 @@ class ThirdBodyGravity : public AccelerationDisturbance { /** * @fn ThirdBodyGravity * @brief Constructor + * @param [in] is_calc_enabled: Calculation flag */ - ThirdBodyGravity(std::set third_body_list); + ThirdBodyGravity(std::set third_body_list, const bool is_calc_enabled = true); /** * @fn ~ThirdBodyGravity * @brief Destructor From 4f260c6c36bc6449aefcba6c321424885d788c5c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:33:59 +0100 Subject: [PATCH 0409/1086] Add unit for force and torque --- src/disturbances/air_drag.cpp | 4 ++-- src/disturbances/disturbance.hpp | 12 ++++++------ src/disturbances/gravity_gradient.cpp | 10 ++++------ src/disturbances/magnetic_disturbance.cpp | 11 ++++------- src/disturbances/simple_disturbance.hpp | 4 ++-- .../solar_radiation_pressure_disturbance.cpp | 4 ++-- src/disturbances/surface_force.cpp | 9 +++------ 7 files changed, 23 insertions(+), 31 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 79eddd7d1..fa9f39a53 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -97,8 +97,8 @@ string AirDrag::GetLogHeader() const { string AirDrag::GetLogValue() const { string str_tmp = ""; - str_tmp += WriteVector(torque_b_); - str_tmp += WriteVector(force_b_); + str_tmp += WriteVector(torque_b_Nm_); + str_tmp += WriteVector(force_b_N_); return str_tmp; } diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index ec1f684c7..2f1fbf873 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -20,8 +20,8 @@ class Disturbance { * @param [in] is_calc_enabled: Calculation flag */ Disturbance(const bool is_calc_enabled = true) : is_calc_enabled_(is_calc_enabled) { - force_b_ = libra::Vector<3>(0.0); - torque_b_ = libra::Vector<3>(0.0); + force_b_N_ = libra::Vector<3>(0.0); + torque_b_Nm_ = libra::Vector<3>(0.0); acceleration_b_ = libra::Vector<3>(0.0); acceleration_b_ = libra::Vector<3>(0.0); } @@ -30,12 +30,12 @@ class Disturbance { * @fn GetTorque * @brief Return the disturbance torque in the body frame [Nm] */ - virtual inline libra::Vector<3> GetTorque() { return torque_b_; } + virtual inline libra::Vector<3> GetTorque() { return torque_b_Nm_; } /** * @fn GetTorque * @brief Return the disturbance force in the body frame [N] */ - virtual inline libra::Vector<3> GetForce() { return force_b_; } + virtual inline libra::Vector<3> GetForce() { return force_b_N_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the body frame [m/s2] @@ -49,8 +49,8 @@ class Disturbance { protected: bool is_calc_enabled_; //!< Flag to calculate the disturbance - libra::Vector<3> force_b_; //!< Disturbance force in the body frame [N] - libra::Vector<3> torque_b_; //!< Disturbance torque in the body frame [Nm] + libra::Vector<3> force_b_N_; //!< Disturbance force in the body frame [N] + libra::Vector<3> torque_b_Nm_; //!< Disturbance torque in the body frame [Nm] libra::Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] libra::Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] }; diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index a19fb85b1..f4353b995 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -16,9 +16,7 @@ using namespace std; GravityGradient::GravityGradient(const bool is_calc_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calc_enabled) {} -GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), mu_m3_s2_(mu_m3_s2) { - fill_up(torque_b_, 0.0); -} +GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), mu_m3_s2_(mu_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { CalcTorque(local_env.GetCelesInfo().GetCenterBodyPosFromSC_b(), @@ -31,8 +29,8 @@ Vector<3> GravityGradient::CalcTorque(const Vector<3> r_b_m, const Matrix<3, 3> u_b /= r_norm_m; double coeff = 3.0 * mu_m3_s2_ / pow(r_norm_m, 3.0); - torque_b_ = coeff * outer_product(u_b, I_b_kgm2 * u_b); - return torque_b_; + torque_b_Nm_ = coeff * outer_product(u_b, I_b_kgm2 * u_b); + return torque_b_Nm_; } string GravityGradient::GetLogHeader() const { @@ -46,7 +44,7 @@ string GravityGradient::GetLogHeader() const { string GravityGradient::GetLogValue() const { string str_tmp = ""; - str_tmp += WriteVector(torque_b_); + str_tmp += WriteVector(torque_b_Nm_); return str_tmp; } diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 291ffce1c..5ea159b79 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -17,17 +17,14 @@ using namespace std; MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), rmm_params_(rmm_params) { - for (int i = 0; i < 3; ++i) { - torque_b_[i] = 0; - } mag_unit_ = 1.0E-9; // [nT] -> [T] rmm_b_ = rmm_params_.GetRMMConst_b(); } Vector<3> MagDisturbance::CalcTorque(const Vector<3>& mag_b) { CalcRMM(); - torque_b_ = mag_unit_ * outer_product(rmm_b_, mag_b); - return torque_b_; + torque_b_Nm_ = mag_unit_ * outer_product(rmm_b_, mag_b); + return torque_b_Nm_; } void MagDisturbance::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { @@ -50,7 +47,7 @@ void MagDisturbance::CalcRMM() { } void MagDisturbance::PrintTorque() { - cout << "MgDist_Torque_b =(" << torque_b_[0] << "," << torque_b_[1] << "," << torque_b_[2] << ") Nm"; + cout << "MgDist_Torque_b =(" << torque_b_Nm_[0] << "," << torque_b_Nm_[1] << "," << torque_b_Nm_[2] << ") Nm"; cout << endl; } @@ -67,7 +64,7 @@ string MagDisturbance::GetLogValue() const { string str_tmp = ""; str_tmp += WriteVector(rmm_b_); - str_tmp += WriteVector(torque_b_); + str_tmp += WriteVector(torque_b_Nm_); return str_tmp; } diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 806a162d6..94f185444 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -39,8 +39,8 @@ class SimpleDisturbance : public Disturbance, public ILoggable { if (is_calc_enabled_) { Update(local_env, dynamics); } else { - force_b_ *= 0; - torque_b_ *= 0; + force_b_N_ *= 0; + torque_b_Nm_ *= 0; } } diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 86f12bcd3..247fc8e4b 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -44,8 +44,8 @@ std::string SolarRadiation::GetLogHeader() const { std::string SolarRadiation::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(torque_b_); - str_tmp += WriteVector(force_b_); + str_tmp += WriteVector(torque_b_Nm_); + str_tmp += WriteVector(force_b_N_); return str_tmp; } diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 38fbd97f5..8559b0445 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -13,9 +13,6 @@ using namespace libra; SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), surfaces_(surfaces), cg_b_(cg_b) { - force_b_ = Vector<3>(0); - torque_b_ = Vector<3>(0); - // Initialize vectors int num = surfaces_.size(); normal_coef_.assign(num, 0.0); @@ -47,9 +44,9 @@ Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { Trq += Ts; } } - force_b_ = Force; - torque_b_ = Trq; - return torque_b_; + force_b_N_ = Force; + torque_b_Nm_ = Trq; + return torque_b_Nm_; } void SurfaceForce::CalcTheta(Vector<3>& input_b) { From 69708588c840f245d63221d326a83760ee483faa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:35:38 +0100 Subject: [PATCH 0410/1086] Add unit for acceleration --- src/disturbances/acceleration_disturbance.hpp | 4 ++-- src/disturbances/disturbance.hpp | 18 +++++++++--------- src/disturbances/geopotential.cpp | 2 +- src/disturbances/third_body_gravity.cpp | 10 ++++------ 4 files changed, 16 insertions(+), 18 deletions(-) diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index dd3b12a64..0c2e4a0d1 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -36,8 +36,8 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { if (is_calc_enabled_) { Update(local_env, dynamics); } else { - acceleration_b_ *= 0; - acceleration_i_ *= 0; + acceleration_b_m_s2_ *= 0; + acceleration_i_m_s2_ *= 0; } } diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 2f1fbf873..4ee12bcc4 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -22,8 +22,8 @@ class Disturbance { Disturbance(const bool is_calc_enabled = true) : is_calc_enabled_(is_calc_enabled) { force_b_N_ = libra::Vector<3>(0.0); torque_b_Nm_ = libra::Vector<3>(0.0); - acceleration_b_ = libra::Vector<3>(0.0); - acceleration_b_ = libra::Vector<3>(0.0); + acceleration_b_m_s2_ = libra::Vector<3>(0.0); + acceleration_b_m_s2_ = libra::Vector<3>(0.0); } /** @@ -40,19 +40,19 @@ class Disturbance { * @fn GetTorque * @brief Return the disturbance acceleration in the body frame [m/s2] */ - virtual inline libra::Vector<3> GetAccelerationB() { return acceleration_b_; } + virtual inline libra::Vector<3> GetAccelerationB() { return acceleration_b_m_s2_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the inertial frame [m/s2] */ - virtual inline libra::Vector<3> GetAccelerationI() { return acceleration_i_; } + virtual inline libra::Vector<3> GetAccelerationI() { return acceleration_i_m_s2_; } protected: - bool is_calc_enabled_; //!< Flag to calculate the disturbance - libra::Vector<3> force_b_N_; //!< Disturbance force in the body frame [N] - libra::Vector<3> torque_b_Nm_; //!< Disturbance torque in the body frame [Nm] - libra::Vector<3> acceleration_b_; //!< Disturbance acceleration in the body frame [m/s2] - libra::Vector<3> acceleration_i_; //!< Disturbance acceleration in the inertial frame [m/s2] + bool is_calc_enabled_; //!< Flag to calculate the disturbance + libra::Vector<3> force_b_N_; //!< Disturbance force in the body frame [N] + libra::Vector<3> torque_b_Nm_; //!< Disturbance torque in the body frame [Nm] + libra::Vector<3> acceleration_b_m_s2_; //!< Disturbance acceleration in the body frame [m/s2] + libra::Vector<3> acceleration_i_m_s2_; //!< Disturbance acceleration in the inertial frame [m/s2] }; #endif // S2E_DISTURBANCES_DISTURBANCE_HPP_ diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index c94227550..6e858255e 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -82,7 +82,7 @@ void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dyn Matrix<3, 3> trans_eci2ecef_ = local_env.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); - acceleration_i_ = trans_ecef2eci * acc_ecef_; + acceleration_i_m_s2_ = trans_ecef2eci * acc_ecef_; } void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef) { diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 742c3b89a..1728d5fcc 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -6,14 +6,12 @@ #include "third_body_gravity.hpp" ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calc_enabled) - : AccelerationDisturbance(is_calc_enabled), third_body_list_(third_body_list) { - acceleration_i_ *= 0; -} + : AccelerationDisturbance(is_calc_enabled), third_body_list_(third_body_list) {} ThirdBodyGravity::~ThirdBodyGravity() {} void ThirdBodyGravity::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { - acceleration_i_ = libra::Vector<3>(0); // initialize + acceleration_i_m_s2_ = libra::Vector<3>(0); // initialize libra::Vector<3> sat_pos_i = dynamics.GetOrbit().GetSatPosition_i(); // position of the spacecraft // from the center object @@ -25,7 +23,7 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_env, const Dynamics& double gravity_constant = local_env.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); thirdbody_acc_i_ = CalcAcceleration(third_body_pos_i, third_body_pos_from_sc_i, gravity_constant); - acceleration_i_ += thirdbody_acc_i_; + acceleration_i_m_s2_ += thirdbody_acc_i_; } } @@ -50,7 +48,7 @@ std::string ThirdBodyGravity::GetLogHeader() const { std::string ThirdBodyGravity::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(acceleration_i_); + str_tmp += WriteVector(acceleration_i_m_s2_); return str_tmp; } From c839ba8c3034e0c9873ffb55e89439832e50678b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:37:55 +0100 Subject: [PATCH 0411/1086] Add unit into functions name --- src/disturbances/disturbance.hpp | 8 ++++---- src/disturbances/disturbances.cpp | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 4ee12bcc4..8963a6ada 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -30,22 +30,22 @@ class Disturbance { * @fn GetTorque * @brief Return the disturbance torque in the body frame [Nm] */ - virtual inline libra::Vector<3> GetTorque() { return torque_b_Nm_; } + virtual inline libra::Vector<3> GetTorque_b_Nm() { return torque_b_Nm_; } /** * @fn GetTorque * @brief Return the disturbance force in the body frame [N] */ - virtual inline libra::Vector<3> GetForce() { return force_b_N_; } + virtual inline libra::Vector<3> GetForce_b_N() { return force_b_N_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the body frame [m/s2] */ - virtual inline libra::Vector<3> GetAccelerationB() { return acceleration_b_m_s2_; } + virtual inline libra::Vector<3> GetAcceleration_b_m_s2() { return acceleration_b_m_s2_; } /** * @fn GetTorque * @brief Return the disturbance acceleration in the inertial frame [m/s2] */ - virtual inline libra::Vector<3> GetAccelerationI() { return acceleration_i_m_s2_; } + virtual inline libra::Vector<3> GetAcceleration_i_m_s2() { return acceleration_i_m_s2_; } protected: bool is_calc_enabled_; //!< Flag to calculate the disturbance diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 84412025f..e7e751a3f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -37,8 +37,8 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn InitializeForceAndTorque(); for (auto dist : disturbances_) { dist->UpdateIfEnabled(local_env, dynamics); - sum_torque_ += dist->GetTorque(); - sum_force_ += dist->GetForce(); + sum_torque_ += dist->GetTorque_b_Nm(); + sum_force_ += dist->GetForce_b_N(); } } // Update disturbances that depend only on the position @@ -46,7 +46,7 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn InitializeAcceleration(); for (auto acc_dist : acc_disturbances_) { acc_dist->UpdateIfEnabled(local_env, dynamics); - sum_acceleration_i_ += acc_dist->GetAccelerationI(); + sum_acceleration_i_ += acc_dist->GetAcceleration_i_m_s2(); } } } From c78400a035b92525db35ea4858c76d3d28592673 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:40:27 +0100 Subject: [PATCH 0412/1086] Fix 0 to 0.0 --- src/disturbances/acceleration_disturbance.hpp | 4 ++-- src/disturbances/simple_disturbance.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index 0c2e4a0d1..f99f39d6f 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -36,8 +36,8 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { if (is_calc_enabled_) { Update(local_env, dynamics); } else { - acceleration_b_m_s2_ *= 0; - acceleration_i_m_s2_ *= 0; + acceleration_b_m_s2_ *= 0.0; + acceleration_i_m_s2_ *= 0.0; } } diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 94f185444..262fea9af 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -39,8 +39,8 @@ class SimpleDisturbance : public Disturbance, public ILoggable { if (is_calc_enabled_) { Update(local_env, dynamics); } else { - force_b_N_ *= 0; - torque_b_Nm_ *= 0; + force_b_N_ *= 0.0; + torque_b_Nm_ *= 0.0; } } From b2d1bdd7bae579f6e33b036c4f3000a18e2d072b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:42:43 +0100 Subject: [PATCH 0413/1086] Fix variable name --- src/disturbances/acceleration_disturbance.hpp | 6 +++--- src/disturbances/air_drag.cpp | 4 ++-- src/disturbances/air_drag.hpp | 4 ++-- src/disturbances/disturbance.hpp | 6 +++--- src/disturbances/geopotential.cpp | 4 ++-- src/disturbances/geopotential.hpp | 4 ++-- src/disturbances/gravity_gradient.cpp | 6 ++++-- src/disturbances/gravity_gradient.hpp | 8 ++++---- src/disturbances/magnetic_disturbance.cpp | 4 ++-- src/disturbances/magnetic_disturbance.hpp | 4 ++-- src/disturbances/simple_disturbance.hpp | 6 +++--- src/disturbances/solar_radiation_pressure_disturbance.cpp | 4 ++-- src/disturbances/solar_radiation_pressure_disturbance.hpp | 4 ++-- src/disturbances/surface_force.cpp | 4 ++-- src/disturbances/surface_force.hpp | 4 ++-- src/disturbances/third_body_gravity.cpp | 4 ++-- src/disturbances/third_body_gravity.hpp | 4 ++-- 17 files changed, 41 insertions(+), 39 deletions(-) diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index f99f39d6f..f9be52606 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -19,9 +19,9 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { /** * @fn AccelerationDisturbance * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - AccelerationDisturbance(const bool is_calc_enabled = true) : Disturbance(is_calc_enabled) {} + AccelerationDisturbance(const bool is_calculation_enabled = true) : Disturbance(is_calculation_enabled) {} /** * @fn ~AccelerationDisturbance * @brief Destructor @@ -33,7 +33,7 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { * @brief Update calculated disturbance when the calculation flag is true */ virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { - if (is_calc_enabled_) { + if (is_calculation_enabled_) { Update(local_env, dynamics); } else { acceleration_b_m_s2_ *= 0.0; diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index fa9f39a53..57254867c 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -16,8 +16,8 @@ using namespace std; using namespace libra; AirDrag::AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, - const bool is_calc_enabled) - : SurfaceForce(surfaces, cg_b, is_calc_enabled) { + const bool is_calculation_enabled) + : SurfaceForce(surfaces, cg_b, is_calculation_enabled) { int num = surfaces_.size(); Ct_.assign(num, 1.0); Cn_.assign(num, 0.0); diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 3762a1daa..41f91e5d6 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -27,10 +27,10 @@ class AirDrag : public SurfaceForce { /** * @fn AirDrag * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, - const bool is_calc_enabled = true); + const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 8963a6ada..25c26ba3c 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -17,9 +17,9 @@ class Disturbance { /** * @fn Disturbance * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - Disturbance(const bool is_calc_enabled = true) : is_calc_enabled_(is_calc_enabled) { + Disturbance(const bool is_calculation_enabled = true) : is_calculation_enabled_(is_calculation_enabled) { force_b_N_ = libra::Vector<3>(0.0); torque_b_Nm_ = libra::Vector<3>(0.0); acceleration_b_m_s2_ = libra::Vector<3>(0.0); @@ -48,7 +48,7 @@ class Disturbance { virtual inline libra::Vector<3> GetAcceleration_i_m_s2() { return acceleration_i_m_s2_; } protected: - bool is_calc_enabled_; //!< Flag to calculate the disturbance + bool is_calculation_enabled_; //!< Flag to calculate the disturbance libra::Vector<3> force_b_N_; //!< Disturbance force in the body frame [N] libra::Vector<3> torque_b_Nm_; //!< Disturbance torque in the body frame [Nm] libra::Vector<3> acceleration_b_m_s2_; //!< Disturbance acceleration in the body frame [m/s2] diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 6e858255e..b29793c66 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -17,8 +17,8 @@ using namespace std; -GeoPotential::GeoPotential(const int degree, const string file_path, const bool is_calc_enabled) - : AccelerationDisturbance(is_calc_enabled), degree_(degree) { +GeoPotential::GeoPotential(const int degree, const string file_path, const bool is_calculation_enabled) + : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize acc_ecef_ = Vector<3>(0); debug_pos_ecef_ = Vector<3>(0); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index e29a62ea9..654c9983b 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -26,9 +26,9 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn GeoPotential * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - GeoPotential(const int degree, const std::string file_path, const bool is_calc_enabled = true); + GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index f4353b995..32a78b55f 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -14,9 +14,11 @@ using namespace std; -GravityGradient::GravityGradient(const bool is_calc_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calc_enabled) {} +GravityGradient::GravityGradient(const bool is_calculation_enabled) + : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calculation_enabled) {} -GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calc_enabled) : SimpleDisturbance(is_calc_enabled), mu_m3_s2_(mu_m3_s2) {} +GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculation_enabled) + : SimpleDisturbance(is_calculation_enabled), mu_m3_s2_(mu_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { CalcTorque(local_env.GetCelesInfo().GetCenterBodyPosFromSC_b(), diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 5b9a9e03a..a063dd0eb 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -26,17 +26,17 @@ class GravityGradient : public SimpleDisturbance { /** * @fn GeoPotential * @brief Default Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag * @note mu is automatically set as earth's gravitational constant */ - GravityGradient(const bool is_calc_enabled = true); + GravityGradient(const bool is_calculation_enabled = true); /** * @fn GeoPotential * @brief Constructor * @param [in] mu_m3_s2: Gravitational constant [m3/s2] - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - GravityGradient(const double mu_m3_s2, const bool is_calc_enabled = true); + GravityGradient(const double mu_m3_s2, const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 5ea159b79..65e9b1d9c 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -15,8 +15,8 @@ using libra::NormalRand; using namespace std; -MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calc_enabled) - : SimpleDisturbance(is_calc_enabled), rmm_params_(rmm_params) { +MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) + : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { mag_unit_ = 1.0E-9; // [nT] -> [T] rmm_b_ = rmm_params_.GetRMMConst_b(); } diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 62d77c7c8..df7ef28a9 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -24,9 +24,9 @@ class MagDisturbance : public SimpleDisturbance { /** * @fn MagDisturbance * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - MagDisturbance(const RMMParams& rmm_params, const bool is_calc_enabled = true); + MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled = true); /** * @fn CalcRMM diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 262fea9af..974a81b79 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -21,9 +21,9 @@ class SimpleDisturbance : public Disturbance, public ILoggable { /** * @fn SimpleDisturbance * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - SimpleDisturbance(const bool is_calc_enabled = true) : Disturbance(is_calc_enabled) {} + SimpleDisturbance(const bool is_calculation_enabled = true) : Disturbance(is_calculation_enabled) {} /** * @fn ~SimpleDisturbance @@ -36,7 +36,7 @@ class SimpleDisturbance : public Disturbance, public ILoggable { * @brief Update calculated disturbance when the calculation flag is true */ virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { - if (is_calc_enabled_) { + if (is_calculation_enabled_) { Update(local_env, dynamics); } else { force_b_N_ *= 0.0; diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 247fc8e4b..f6b5a65da 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,8 +9,8 @@ #include "../interface/log_output/log_utility.hpp" -SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled) - : SurfaceForce(surfaces, cg_b, is_calc_enabled) {} +SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled) + : SurfaceForce(surfaces, cg_b, is_calculation_enabled) {} void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 20a3e4202..6cb92b512 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -23,9 +23,9 @@ class SolarRadiation : public SurfaceForce { /** * @fn SolarRadiation * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled = true); + SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 8559b0445..4ec3b43b1 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -11,8 +11,8 @@ using libra::Vector; using namespace libra; -SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled) - : SimpleDisturbance(is_calc_enabled), surfaces_(surfaces), cg_b_(cg_b) { +SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled) + : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), cg_b_(cg_b) { // Initialize vectors int num = surfaces_.size(); normal_coef_.assign(num, 0.0); diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index c53321cdb..2ca134c56 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -26,9 +26,9 @@ class SurfaceForce : public SimpleDisturbance { /** * @fn SurfaceForce * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calc_enabled = true); + SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled = true); /** * @fn ~SurfaceForce * @brief Destructor diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 1728d5fcc..c67b1218a 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -5,8 +5,8 @@ #include "third_body_gravity.hpp" -ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calc_enabled) - : AccelerationDisturbance(is_calc_enabled), third_body_list_(third_body_list) {} +ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calculation_enabled) + : AccelerationDisturbance(is_calculation_enabled), third_body_list_(third_body_list) {} ThirdBodyGravity::~ThirdBodyGravity() {} diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 05ffb635b..1ab77ce53 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -23,9 +23,9 @@ class ThirdBodyGravity : public AccelerationDisturbance { /** * @fn ThirdBodyGravity * @brief Constructor - * @param [in] is_calc_enabled: Calculation flag + * @param [in] is_calculation_enabled: Calculation flag */ - ThirdBodyGravity(std::set third_body_list, const bool is_calc_enabled = true); + ThirdBodyGravity(std::set third_body_list, const bool is_calculation_enabled = true); /** * @fn ~ThirdBodyGravity * @brief Destructor From a79370a7a660edb61dbccdb25c63be7f414d61c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:43:58 +0100 Subject: [PATCH 0414/1086] Fix argument name --- src/disturbances/acceleration_disturbance.hpp | 6 +++--- src/disturbances/simple_disturbance.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp index f9be52606..f9803e129 100644 --- a/src/disturbances/acceleration_disturbance.hpp +++ b/src/disturbances/acceleration_disturbance.hpp @@ -32,9 +32,9 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { * @fn UpdateIfEnabled * @brief Update calculated disturbance when the calculation flag is true */ - virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { + virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { if (is_calculation_enabled_) { - Update(local_env, dynamics); + Update(local_environment, dynamics); } else { acceleration_b_m_s2_ *= 0.0; acceleration_i_m_s2_ *= 0.0; @@ -45,7 +45,7 @@ class AccelerationDisturbance : public Disturbance, public ILoggable { * @fn Update * @brief Pure virtual function to define the disturbance calculation */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; }; #endif // S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index 974a81b79..d03fb07bc 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -35,9 +35,9 @@ class SimpleDisturbance : public Disturbance, public ILoggable { * @fn UpdateIfEnabled * @brief Update calculated disturbance when the calculation flag is true */ - virtual inline void UpdateIfEnabled(const LocalEnvironment& local_env, const Dynamics& dynamics) { + virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { if (is_calculation_enabled_) { - Update(local_env, dynamics); + Update(local_environment, dynamics); } else { force_b_N_ *= 0.0; torque_b_Nm_ *= 0.0; @@ -48,7 +48,7 @@ class SimpleDisturbance : public Disturbance, public ILoggable { * @fn Update * @brief Pure virtual function to define the disturbance calculation */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics) = 0; + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; }; #endif // S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ From f4181d4ce3264c841eddac5792c0debd69e42ecf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 11:46:42 +0100 Subject: [PATCH 0415/1086] Rename cg_b --- src/disturbances/surface_force.cpp | 6 +++--- src/disturbances/surface_force.hpp | 8 +++++--- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 4ec3b43b1..597ea78c3 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -11,8 +11,8 @@ using libra::Vector; using namespace libra; -SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), cg_b_(cg_b) { +SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) + : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { // Initialize vectors int num = surfaces_.size(); normal_coef_.assign(num, 0.0); @@ -40,7 +40,7 @@ Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { Vector<3> Fs = -1.0 * normal_coef_[i] * normal + tangential_coef_[i] * s; Force += Fs; // calc torque - Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - cg_b_, Fs); + Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, Fs); Trq += Ts; } } diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 2ca134c56..4a98c498c 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -26,9 +26,11 @@ class SurfaceForce : public SimpleDisturbance { /** * @fn SurfaceForce * @brief Constructor + * @param [in] surfaces: Surface information of the spacecraft + * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] * @param [in] is_calculation_enabled: Calculation flag */ - SurfaceForce(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled = true); + SurfaceForce(const vector& surfaces, const Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); /** * @fn ~SurfaceForce * @brief Destructor @@ -37,8 +39,8 @@ class SurfaceForce : public SimpleDisturbance { protected: // Spacecraft Structure parameters - const vector& surfaces_; //!< List of surfaces - const Vector<3>& cg_b_; //!< Position vector of the center of mass at body frame [m] + const vector& surfaces_; //!< List of surfaces + const Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass at body frame [m] // Internal calculated variables vector normal_coef_; //!< coefficients for out-plane force for each surface From 50f9b954fcc9340c628efc66c52dbce997e0daaf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 12:59:19 +0100 Subject: [PATCH 0416/1086] Rename surface force variables --- src/disturbances/air_drag.cpp | 8 ++++---- .../solar_radiation_pressure_disturbance.cpp | 6 +++--- src/disturbances/surface_force.cpp | 16 ++++++++-------- src/disturbances/surface_force.hpp | 8 ++++---- 4 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 57254867c..1c0f7f269 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -39,8 +39,8 @@ void AirDrag::CalcCoef(Vector<3>& vel_b, double air_dens) { CalCnCt(vel_b); for (size_t i = 0; i < surfaces_.size(); i++) { double k = 0.5 * rho_ * vel_b_norm_m * vel_b_norm_m * surfaces_[i].GetArea(); - normal_coef_[i] = k * Cn_[i]; - tangential_coef_[i] = k * Ct_[i]; + normal_coefficients_[i] = k * Cn_[i]; + tangential_coefficients_[i] = k * Ct_[i]; } } @@ -67,8 +67,8 @@ void AirDrag::CalCnCt(Vector<3>& vel_b) { S = sqrt(M_ * vel_b_norm_m * vel_b_norm_m / (2.0 * environment::boltzmann_constant_J_K * Tw_)); // CalcTheta(vel_b); for (size_t i = 0; i < surfaces_.size(); i++) { - double Sn = S * cosX[i]; - double St = S * sinX[i]; + double Sn = S * cos_theta_[i]; + double St = S * sin_theta_[i]; double diffuse = 1.0 - surfaces_[i].GetAirSpecularity(); Cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * funcPi(Sn) / (S * S) + diffuse / 2.0 * funcChi(Sn) / (S * S) * sqrt(Tw_ / Tm_); Ct_[i] = diffuse * St * funcChi(Sn) / (sqrt(libra::pi) * S * S); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index f6b5a65da..412256dbb 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -26,9 +26,9 @@ void SolarRadiation::CalcCoef(Vector<3>& input_b, double item) { double area = surfaces_[i].GetArea(); double reflectivity = surfaces_[i].GetReflectivity(); double specularity = surfaces_[i].GetSpecularity(); - normal_coef_[i] = - area * item * ((1.0 + reflectivity * specularity) * pow(cosX[i], 2.0) + 2.0 / 3.0 * reflectivity * (1.0 - specularity) * cosX[i]); - tangential_coef_[i] = area * item * (1.0 - reflectivity * specularity) * cosX[i] * sinX[i]; + normal_coefficients_[i] = + area * item * ((1.0 + reflectivity * specularity) * pow(cos_theta_[i], 2.0) + 2.0 / 3.0 * reflectivity * (1.0 - specularity) * cos_theta_[i]); + tangential_coefficients_[i] = area * item * (1.0 - reflectivity * specularity) * cos_theta_[i] * sin_theta_[i]; } } diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 597ea78c3..9a64b56e4 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -15,10 +15,10 @@ SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cen : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { // Initialize vectors int num = surfaces_.size(); - normal_coef_.assign(num, 0.0); - tangential_coef_.assign(num, 0.0); - cosX.assign(num, 0.0); - sinX.assign(num, 0.0); + normal_coefficients_.assign(num, 0.0); + tangential_coefficients_.assign(num, 0.0); + cos_theta_.assign(num, 0.0); + sin_theta_.assign(num, 0.0); } Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { @@ -30,14 +30,14 @@ Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { - if (cosX[i] > 0) { // if the surface faces to the disturbance source (sun or air) + if (cos_theta_[i] > 0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force Vector<3> normal = surfaces_[i].GetNormal(); Vector<3> ncu = outer_product(input_b_normal, normal); Vector<3> ncu_normalized = normalize(ncu); Vector<3> s = outer_product(ncu_normalized, normal); // calc force - Vector<3> Fs = -1.0 * normal_coef_[i] * normal + tangential_coef_[i] * s; + Vector<3> Fs = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * s; Force += Fs; // calc torque Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, Fs); @@ -54,7 +54,7 @@ void SurfaceForce::CalcTheta(Vector<3>& input_b) { normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { - cosX[i] = inner_product(surfaces_[i].GetNormal(), input_b_normal); - sinX[i] = sqrt(1.0 - cosX[i] * cosX[i]); + cos_theta_[i] = inner_product(surfaces_[i].GetNormal(), input_b_normal); + sin_theta_[i] = sqrt(1.0 - cos_theta_[i] * cos_theta_[i]); } } diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 4a98c498c..4fb031979 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -43,10 +43,10 @@ class SurfaceForce : public SimpleDisturbance { const Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass at body frame [m] // Internal calculated variables - vector normal_coef_; //!< coefficients for out-plane force for each surface - vector tangential_coef_; //!< coefficients for in-plane force for each surface - vector cosX; //!< cos(X) for each surface (X is the angle b/w normal vector and the direction of disturbance source) - vector sinX; //!< sin(X) for each surface (X is the angle b/w normal vector and the direction of disturbance source) + vector normal_coefficients_; //!< coefficients for out-plane force for each surface + vector tangential_coefficients_; //!< coefficients for in-plane force for each surface + vector cos_theta_; //!< cos(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) + vector sin_theta_; //!< sin(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) // Functions /** From f96ff2d1f0d5b73d057b0a3e045f316ee4026b6c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:08:23 +0100 Subject: [PATCH 0417/1086] Remove using --- src/disturbances/surface_force.cpp | 30 +++++++++++++----------------- src/disturbances/surface_force.hpp | 18 ++++++++---------- 2 files changed, 21 insertions(+), 27 deletions(-) diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 9a64b56e4..32462da0d 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -6,12 +6,8 @@ #include "surface_force.hpp" #include "../library/math/vector.hpp" -using libra::Quaternion; -using libra::Vector; -using namespace libra; - -SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) +SurfaceForce::SurfaceForce(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { // Initialize vectors int num = surfaces_.size(); @@ -21,26 +17,26 @@ SurfaceForce::SurfaceForce(const vector& surfaces, const Vector<3>& cen sin_theta_.assign(num, 0.0); } -Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { +libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_b, double item) { CalcTheta(input_b); CalcCoef(input_b, item); - Vector<3> Force(0.0); - Vector<3> Trq(0.0); - Vector<3> input_b_normal(input_b); + libra::Vector<3> Force(0.0); + libra::Vector<3> Trq(0.0); + libra::Vector<3> input_b_normal(input_b); normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { if (cos_theta_[i] > 0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force - Vector<3> normal = surfaces_[i].GetNormal(); - Vector<3> ncu = outer_product(input_b_normal, normal); - Vector<3> ncu_normalized = normalize(ncu); - Vector<3> s = outer_product(ncu_normalized, normal); + libra::Vector<3> normal = surfaces_[i].GetNormal(); + libra::Vector<3> ncu = outer_product(input_b_normal, normal); + libra::Vector<3> ncu_normalized = normalize(ncu); + libra::Vector<3> s = outer_product(ncu_normalized, normal); // calc force - Vector<3> Fs = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * s; + libra::Vector<3> Fs = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * s; Force += Fs; // calc torque - Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, Fs); + libra::Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, Fs); Trq += Ts; } } @@ -49,8 +45,8 @@ Vector<3> SurfaceForce::CalcTorqueForce(Vector<3>& input_b, double item) { return torque_b_Nm_; } -void SurfaceForce::CalcTheta(Vector<3>& input_b) { - Vector<3> input_b_normal(input_b); +void SurfaceForce::CalcTheta(libra::Vector<3>& input_b) { + libra::Vector<3> input_b_normal(input_b); normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 4fb031979..ba693b9e3 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -8,14 +8,12 @@ #ifndef S2E_DISTURBANCES_SURFACE_FORCE_HPP_ #define S2E_DISTURBANCES_SURFACE_FORCE_HPP_ +#include + #include "../library/math/quaternion.hpp" #include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" #include "simple_disturbance.hpp" -using libra::Quaternion; -using libra::Vector; - -#include /** * @class ThirdBodyGravity @@ -30,7 +28,7 @@ class SurfaceForce : public SimpleDisturbance { * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] * @param [in] is_calculation_enabled: Calculation flag */ - SurfaceForce(const vector& surfaces, const Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); + SurfaceForce(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); /** * @fn ~SurfaceForce * @brief Destructor @@ -39,8 +37,8 @@ class SurfaceForce : public SimpleDisturbance { protected: // Spacecraft Structure parameters - const vector& surfaces_; //!< List of surfaces - const Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass at body frame [m] + const vector& surfaces_; //!< List of surfaces + const libra::Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass at body frame [m] // Internal calculated variables vector normal_coefficients_; //!< coefficients for out-plane force for each surface @@ -56,13 +54,13 @@ class SurfaceForce : public SimpleDisturbance { * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) * @return Calculated disturbance torque in body frame [Nm] */ - Vector<3> CalcTorqueForce(Vector<3>& input_b, double item); + libra::Vector<3> CalcTorqueForce(libra::Vector<3>& input_b, double item); /** * @fn CalcTheta * @brief Calculate cosX and sinX * @param [in] input_b: Direction of disturbance source at the body frame */ - void CalcTheta(Vector<3>& input_b); + void CalcTheta(libra::Vector<3>& input_b); /** * @fn CalcCoef @@ -70,7 +68,7 @@ class SurfaceForce : public SimpleDisturbance { * @param [in] input_b: Direction of disturbance source at the body frame * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) */ - virtual void CalcCoef(Vector<3>& input_b, double item) = 0; + virtual void CalcCoef(libra::Vector<3>& input_b, double item) = 0; }; #endif // S2E_DISTURBANCES_SURFACE_FORCE_HPP_ From 93a16af3c57c73c1e7f988b5cc7f33f8030cb44f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:11:48 +0100 Subject: [PATCH 0418/1086] Fix function name --- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/surface_force.cpp | 2 +- src/disturbances/surface_force.hpp | 4 ++-- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 1c0f7f269..4de02c5bd 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -33,7 +33,7 @@ void AirDrag::Update(const LocalEnvironment& local_env, const Dynamics& dynamics CalcTorqueForce(tmp, air_dens); } -void AirDrag::CalcCoef(Vector<3>& vel_b, double air_dens) { +void AirDrag::CalcCoefficients(Vector<3>& vel_b, double air_dens) { double vel_b_norm_m = norm(vel_b); rho_ = air_dens; CalCnCt(vel_b); diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 41f91e5d6..847ab2ad2 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -68,7 +68,7 @@ class AirDrag : public SurfaceForce { * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ - void CalcCoef(Vector<3>& vel_b, double air_dens); + void CalcCoefficients(Vector<3>& vel_b, double air_dens); // internal function for calculation /** diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 412256dbb..c7f2e4bdb 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -19,7 +19,7 @@ void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& d CalcTorqueForce(tmp, local_env.GetSrp().CalcTruePressure()); } -void SolarRadiation::CalcCoef(Vector<3>& input_b, double item) { +void SolarRadiation::CalcCoefficients(Vector<3>& input_b, double item) { UNUSED(input_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 6cb92b512..06c5351de 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -52,7 +52,7 @@ class SolarRadiation : public SurfaceForce { * @param [in] input_b: Direction vector of the sun at the body frame * @param [in] item: Solar pressure [N/m^2] */ - virtual void CalcCoef(Vector<3>& input_b, double item); + void CalcCoefficients(Vector<3>& input_b, double item); }; #endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 32462da0d..3573724e0 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -19,7 +19,7 @@ SurfaceForce::SurfaceForce(const vector& surfaces, const libra::Vector< libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_b, double item) { CalcTheta(input_b); - CalcCoef(input_b, item); + CalcCoefficients(input_b, item); libra::Vector<3> Force(0.0); libra::Vector<3> Trq(0.0); libra::Vector<3> input_b_normal(input_b); diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index ba693b9e3..243b3fba7 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -63,12 +63,12 @@ class SurfaceForce : public SimpleDisturbance { void CalcTheta(libra::Vector<3>& input_b); /** - * @fn CalcCoef + * @fn CalcCoefficients * @brief Pure virtual function to define the calculation of the disturbance coefficients * @param [in] input_b: Direction of disturbance source at the body frame * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) */ - virtual void CalcCoef(libra::Vector<3>& input_b, double item) = 0; + virtual void CalcCoefficients(libra::Vector<3>& input_b, double item) = 0; }; #endif // S2E_DISTURBANCES_SURFACE_FORCE_HPP_ From 11d86e6309a4cfe9bfca7165f2296c89d480d85f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:14:46 +0100 Subject: [PATCH 0419/1086] Fix commnets --- src/disturbances/air_drag.hpp | 4 ++-- src/disturbances/solar_radiation_pressure_disturbance.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 847ab2ad2..5281d8889 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -63,8 +63,8 @@ class AirDrag : public SurfaceForce { double M_; //!< Molecular weight [g/mol] /** - * @fn CalcCoef - * @brief Override CalcCoef function of SurfaceForce + * @fn CalcCoefficients + * @brief Override CalcCoefficients function of SurfaceForce * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 06c5351de..087a2a151 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -47,8 +47,8 @@ class SolarRadiation : public SurfaceForce { private: /** - * @fn CalcCoef - * @brief Override CalcCoef function of SurfaceForce + * @fn CalcCoefficients + * @brief Override CalcCoefficients function of SurfaceForce * @param [in] input_b: Direction vector of the sun at the body frame * @param [in] item: Solar pressure [N/m^2] */ From 8384819f943deecd5c79f9c653c32fa47fd7ca58 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:26:09 +0100 Subject: [PATCH 0420/1086] fix local variables --- src/disturbances/surface_force.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 3573724e0..b4c4ce4c0 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -20,28 +20,28 @@ SurfaceForce::SurfaceForce(const vector& surfaces, const libra::Vector< libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_b, double item) { CalcTheta(input_b); CalcCoefficients(input_b, item); - libra::Vector<3> Force(0.0); - libra::Vector<3> Trq(0.0); + + libra::Vector<3> force_b_N(0.0); + libra::Vector<3> torque_b_Nm(0.0); libra::Vector<3> input_b_normal(input_b); normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { - if (cos_theta_[i] > 0) { // if the surface faces to the disturbance source (sun or air) + if (cos_theta_[i] > 0.0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force libra::Vector<3> normal = surfaces_[i].GetNormal(); libra::Vector<3> ncu = outer_product(input_b_normal, normal); libra::Vector<3> ncu_normalized = normalize(ncu); - libra::Vector<3> s = outer_product(ncu_normalized, normal); + libra::Vector<3> in_plane_force_direction = outer_product(ncu_normalized, normal); // calc force - libra::Vector<3> Fs = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * s; - Force += Fs; + libra::Vector<3> force_per_surface_b_N = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * in_plane_force_direction; + force_b_N += force_per_surface_b_N; // calc torque - libra::Vector<3> Ts = outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, Fs); - Trq += Ts; + torque_b_Nm += outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, force_per_surface_b_N); } } - force_b_N_ = Force; - torque_b_Nm_ = Trq; + force_b_N_ = force_b_N; + torque_b_Nm_ = torque_b_Nm; return torque_b_Nm_; } From b6846cc38d62b5ebd06a6e041d8e4c77328e2464 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:29:10 +0100 Subject: [PATCH 0421/1086] Remove using --- src/disturbances/air_drag.cpp | 25 +++++++++++-------------- src/disturbances/air_drag.hpp | 9 +++------ 2 files changed, 14 insertions(+), 20 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 4de02c5bd..3fdefc799 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -12,10 +12,7 @@ #include "../interface/log_output/log_utility.hpp" -using namespace std; -using namespace libra; - -AirDrag::AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, +AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, const bool is_calculation_enabled) : SurfaceForce(surfaces, cg_b, is_calculation_enabled) { int num = surfaces_.size(); @@ -33,7 +30,7 @@ void AirDrag::Update(const LocalEnvironment& local_env, const Dynamics& dynamics CalcTorqueForce(tmp, air_dens); } -void AirDrag::CalcCoefficients(Vector<3>& vel_b, double air_dens) { +void AirDrag::CalcCoefficients(libra::Vector<3>& vel_b, double air_dens) { double vel_b_norm_m = norm(vel_b); rho_ = air_dens; CalCnCt(vel_b); @@ -61,7 +58,7 @@ double AirDrag::funcChi(double s) { void AirDrag::CalCnCt(Vector<3>& vel_b) { double S; double vel_b_norm_m = norm(vel_b); - Vector<3> vel_b_normal(vel_b); + libra::Vector<3> vel_b_normal(vel_b); normalize(vel_b_normal); // Re-emitting speed S = sqrt(M_ * vel_b_norm_m * vel_b_norm_m / (2.0 * environment::boltzmann_constant_J_K * Tw_)); @@ -79,14 +76,14 @@ void AirDrag::CalCnCt(Vector<3>& vel_b) { void AirDrag::PrintParams(void) // for debug { - Vector<3> arms_b = surfaces_[0].GetPosition(); - cout << "px_arm =(" << arms_b[0] << "," << arms_b[1] << "," << arms_b[2] << ") m \n"; - cout << "area =(" << surfaces_[0].GetArea() << "," << surfaces_[1].GetArea() << "," << surfaces_[2].GetArea() << ") m^2 \n"; - cout << "Temperature =(" << Tw_ << "," << Tm_ << ") K \n"; + libra::Vector<3> arms_b = surfaces_[0].GetPosition(); + std::cout << "px_arm =(" << arms_b[0] << "," << arms_b[1] << "," << arms_b[2] << ") m \n"; + std::cout << "area =(" << surfaces_[0].GetArea() << "," << surfaces_[1].GetArea() << "," << surfaces_[2].GetArea() << ") m^2 \n"; + std::cout << "Temperature =(" << Tw_ << "," << Tm_ << ") K \n"; } -string AirDrag::GetLogHeader() const { - string str_tmp = ""; +std::string AirDrag::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteVector("air_drag_torque", "b", "Nm", 3); str_tmp += WriteVector("air_drag_force", "b", "N", 3); @@ -94,8 +91,8 @@ string AirDrag::GetLogHeader() const { return str_tmp; } -string AirDrag::GetLogValue() const { - string str_tmp = ""; +std::string AirDrag::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteVector(torque_b_Nm_); str_tmp += WriteVector(force_b_N_); diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 5281d8889..fb89c9697 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -11,11 +11,8 @@ #include "../environment/local/atmosphere.hpp" #include "../interface/log_output/loggable.hpp" -#include "../library/math/quaternion.hpp" #include "../library/math/vector.hpp" #include "surface_force.hpp" -using libra::Quaternion; -using libra::Vector; #pragma once /** @@ -29,7 +26,7 @@ class AirDrag : public SurfaceForce { * @brief Constructor * @param [in] is_calculation_enabled: Calculation flag */ - AirDrag(const vector& surfaces, const Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, + AirDrag(const vector& surfaces, const libra::Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, const bool is_calculation_enabled = true); /** @@ -68,7 +65,7 @@ class AirDrag : public SurfaceForce { * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ - void CalcCoefficients(Vector<3>& vel_b, double air_dens); + void CalcCoefficients(libra::Vector<3>& vel_b, double air_dens); // internal function for calculation /** @@ -76,7 +73,7 @@ class AirDrag : public SurfaceForce { * @brief Calculate the Cn and Ct * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] */ - void CalCnCt(Vector<3>& vel_b); + void CalCnCt(libra::Vector<3>& vel_b); /** * @fn funcPi * @brief Calculate The Pi function in the algorithm From ed9d8a1e8befa7d958e36fe848a3ac11d8d34724 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:33:35 +0100 Subject: [PATCH 0422/1086] fix argument of constructor --- src/disturbances/air_drag.cpp | 12 ++++++------ src/disturbances/air_drag.hpp | 9 +++++++-- 2 files changed, 13 insertions(+), 8 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 3fdefc799..94b363e3d 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -12,16 +12,16 @@ #include "../interface/log_output/log_utility.hpp" -AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, - const bool is_calculation_enabled) - : SurfaceForce(surfaces, cg_b, is_calculation_enabled) { +AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_degC, + const double molecular_temperature_degC, const double molecular_weight, const bool is_calculation_enabled) + : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) { int num = surfaces_.size(); Ct_.assign(num, 1.0); Cn_.assign(num, 0.0); cnct.assign(num, 0.0); - Tw_ = t_w; - Tm_ = t_m; - M_ = molecular; + Tw_ = wall_temperature_degC; + Tm_ = molecular_temperature_degC; + M_ = molecular_weight; } void AirDrag::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index fb89c9697..0d46a5914 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -24,10 +24,15 @@ class AirDrag : public SurfaceForce { /** * @fn AirDrag * @brief Constructor + * @param [in] surfaces: Surface information of the spacecraft + * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] + * @param [in] wall_temperature_degC: Temperature of surfaces [degC] + * @param [in] molecular_temperature_degC: Temperature of air molecular [degC] + * @param [in] molecular_weight: Molecular weight * @param [in] is_calculation_enabled: Calculation flag */ - AirDrag(const vector& surfaces, const libra::Vector<3>& cg_b, const double t_w, const double t_m, const double molecular, - const bool is_calculation_enabled = true); + AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_degC, + const double molecular_temperature_degC, const double molecular_weight, const bool is_calculation_enabled = true); /** * @fn Update From 8676a5c0ef819584a3bdfa5b87391c464cfc33db Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:34:16 +0100 Subject: [PATCH 0423/1086] fix argument of function --- src/disturbances/air_drag.cpp | 4 ++-- src/disturbances/air_drag.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 94b363e3d..f904158f6 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -24,8 +24,8 @@ AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center M_ = molecular_weight; } -void AirDrag::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { - double air_dens = local_env.GetAtmosphere().GetAirDensity(); +void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { + double air_dens = local_environment.GetAtmosphere().GetAirDensity(); Vector<3> tmp = dynamics.GetOrbit().GetSatVelocity_b(); CalcTorqueForce(tmp, air_dens); } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 0d46a5914..53dcc784c 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -38,7 +38,7 @@ class AirDrag : public SurfaceForce { * @fn Update * @brief Override Updates function of SimpleDisturbance */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); // Override ILoggable /** From ba5d2de89c6047e2378e5934c88702932f286afe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:35:50 +0100 Subject: [PATCH 0424/1086] Add unit --- src/disturbances/air_drag.cpp | 4 ++-- src/disturbances/air_drag.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index f904158f6..6e496c77b 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -32,10 +32,10 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& void AirDrag::CalcCoefficients(libra::Vector<3>& vel_b, double air_dens) { double vel_b_norm_m = norm(vel_b); - rho_ = air_dens; + rho_kg_m3_ = air_dens; CalCnCt(vel_b); for (size_t i = 0; i < surfaces_.size(); i++) { - double k = 0.5 * rho_ * vel_b_norm_m * vel_b_norm_m * surfaces_[i].GetArea(); + double k = 0.5 * rho_kg_m3_ * vel_b_norm_m * vel_b_norm_m * surfaces_[i].GetArea(); normal_coefficients_[i] = k * Cn_[i]; tangential_coefficients_[i] = k * Ct_[i]; } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 53dcc784c..0d8d75495 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -59,7 +59,7 @@ class AirDrag : public SurfaceForce { private: vector Cn_; //!< Coefficients for out-plane force vector Ct_; //!< Coefficients for in-plane force - double rho_; //!< Air density [kg/m^3] + double rho_kg_m3_; //!< Air density [kg/m^3] double Tw_; //!< Temperature of surface [K] double Tm_; //!< Temperature of atmosphere [K] double M_; //!< Molecular weight [g/mol] From 453bc97cc8a2a115fbc0a4c4c5dde04bf8944eaa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:36:53 +0100 Subject: [PATCH 0425/1086] Delete unused debug --- src/disturbances/air_drag.cpp | 11 ----------- src/disturbances/air_drag.hpp | 4 ---- 2 files changed, 15 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 6e496c77b..6454dbe4b 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -18,7 +18,6 @@ AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center int num = surfaces_.size(); Ct_.assign(num, 1.0); Cn_.assign(num, 0.0); - cnct.assign(num, 0.0); Tw_ = wall_temperature_degC; Tm_ = molecular_temperature_degC; M_ = molecular_weight; @@ -69,19 +68,9 @@ void AirDrag::CalCnCt(Vector<3>& vel_b) { double diffuse = 1.0 - surfaces_[i].GetAirSpecularity(); Cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * funcPi(Sn) / (S * S) + diffuse / 2.0 * funcChi(Sn) / (S * S) * sqrt(Tw_ / Tm_); Ct_[i] = diffuse * St * funcChi(Sn) / (sqrt(libra::pi) * S * S); - // for debug - cnct[i] = Ct_[i] / Cn_[i]; } } -void AirDrag::PrintParams(void) // for debug -{ - libra::Vector<3> arms_b = surfaces_[0].GetPosition(); - std::cout << "px_arm =(" << arms_b[0] << "," << arms_b[1] << "," << arms_b[2] << ") m \n"; - std::cout << "area =(" << surfaces_[0].GetArea() << "," << surfaces_[1].GetArea() << "," << surfaces_[2].GetArea() << ") m^2 \n"; - std::cout << "Temperature =(" << Tw_ << "," << Tm_ << ") K \n"; -} - std::string AirDrag::GetLogHeader() const { std::string str_tmp = ""; diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 0d8d75495..bba6ce913 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -52,10 +52,6 @@ class AirDrag : public SurfaceForce { */ virtual std::string GetLogValue() const; - // for debug TODO: remove? - void PrintParams(void); - std::vector cnct; - private: vector Cn_; //!< Coefficients for out-plane force vector Ct_; //!< Coefficients for in-plane force From 0fa2c24290df5428218e1c400e12e2fa2d0b78af Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:41:38 +0100 Subject: [PATCH 0426/1086] fix argument of function --- src/disturbances/air_drag.cpp | 18 ++++++++---------- src/disturbances/air_drag.hpp | 8 ++++---- 2 files changed, 12 insertions(+), 14 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 6454dbe4b..446dd4646 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -29,12 +29,12 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& CalcTorqueForce(tmp, air_dens); } -void AirDrag::CalcCoefficients(libra::Vector<3>& vel_b, double air_dens) { - double vel_b_norm_m = norm(vel_b); +void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens) { + double velocity_norm_m_s = norm(velocity_b_m_s); rho_kg_m3_ = air_dens; - CalCnCt(vel_b); + CalCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { - double k = 0.5 * rho_kg_m3_ * vel_b_norm_m * vel_b_norm_m * surfaces_[i].GetArea(); + double k = 0.5 * rho_kg_m3_ * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); normal_coefficients_[i] = k * Cn_[i]; tangential_coefficients_[i] = k * Ct_[i]; } @@ -54,13 +54,11 @@ double AirDrag::funcChi(double s) { return x; } -void AirDrag::CalCnCt(Vector<3>& vel_b) { - double S; - double vel_b_norm_m = norm(vel_b); - libra::Vector<3> vel_b_normal(vel_b); - normalize(vel_b_normal); +void AirDrag::CalCnCt(Vector<3>& velocity_b_m_s) { + double velocity_norm_m_s = norm(velocity_b_m_s); + // Re-emitting speed - S = sqrt(M_ * vel_b_norm_m * vel_b_norm_m / (2.0 * environment::boltzmann_constant_J_K * Tw_)); + double S = sqrt(M_ * velocity_norm_m_s * velocity_norm_m_s / (2.0 * environment::boltzmann_constant_J_K * Tw_)); // CalcTheta(vel_b); for (size_t i = 0; i < surfaces_.size(); i++) { double Sn = S * cos_theta_[i]; diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index bba6ce913..dbd543230 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -63,18 +63,18 @@ class AirDrag : public SurfaceForce { /** * @fn CalcCoefficients * @brief Override CalcCoefficients function of SurfaceForce - * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] + * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ - void CalcCoefficients(libra::Vector<3>& vel_b, double air_dens); + void CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens); // internal function for calculation /** * @fn CalCnCt * @brief Calculate the Cn and Ct - * @param [in] vel_b: Spacecraft's velocity vector in the body frame [m/s] + * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] */ - void CalCnCt(libra::Vector<3>& vel_b); + void CalCnCt(libra::Vector<3>& velocity_b_m_s); /** * @fn funcPi * @brief Calculate The Pi function in the algorithm From c0004b53a0cc81f5feebcc9532ff9e0194cf4e90 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:43:12 +0100 Subject: [PATCH 0427/1086] Fix privatefunction name --- src/disturbances/air_drag.cpp | 8 ++++---- src/disturbances/air_drag.hpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 446dd4646..8eb180ae9 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -40,14 +40,14 @@ void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens } } -double AirDrag::funcPi(double s) { +double AirDrag::CalcFuncPi(double s) { double x; double erfs = erf(s); // ERF function is defined in math standard library x = s * exp(-s * s) + sqrt(libra::pi) * (s * s + 0.5) * (1.0 + erfs); return x; } -double AirDrag::funcChi(double s) { +double AirDrag::CalcFuncChi(double s) { double x; double erfs = erf(s); x = exp(-s * s) + sqrt(libra::pi) * s * (1.0 + erfs); @@ -64,8 +64,8 @@ void AirDrag::CalCnCt(Vector<3>& velocity_b_m_s) { double Sn = S * cos_theta_[i]; double St = S * sin_theta_[i]; double diffuse = 1.0 - surfaces_[i].GetAirSpecularity(); - Cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * funcPi(Sn) / (S * S) + diffuse / 2.0 * funcChi(Sn) / (S * S) * sqrt(Tw_ / Tm_); - Ct_[i] = diffuse * St * funcChi(Sn) / (sqrt(libra::pi) * S * S); + Cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * CalcFuncPi(Sn) / (S * S) + diffuse / 2.0 * CalcFuncChi(Sn) / (S * S) * sqrt(Tw_ / Tm_); + Ct_[i] = diffuse * St * CalcFuncChi(Sn) / (sqrt(libra::pi) * S * S); } } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index dbd543230..54b4c98b8 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -79,12 +79,12 @@ class AirDrag : public SurfaceForce { * @fn funcPi * @brief Calculate The Pi function in the algorithm */ - double funcPi(double s); + double CalcFuncPi(double s); /** * @fn funcChi * @brief Calculate The Chi function in the algorithm */ - double funcChi(double s); + double CalcFuncChi(double s); }; #endif // S2E_DISTURBANCES_AIR_DRAG_HPP_ From fd0f2f387608005063fe74b3c831b595db3e4d6e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:44:41 +0100 Subject: [PATCH 0428/1086] Unused include --- src/disturbances/air_drag.cpp | 1 - src/disturbances/air_drag.hpp | 1 - 2 files changed, 2 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 8eb180ae9..26442befa 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -7,7 +7,6 @@ #include #include -#include #include #include "../interface/log_output/log_utility.hpp" diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 54b4c98b8..8add4bbbd 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -6,7 +6,6 @@ #ifndef S2E_DISTURBANCES_AIR_DRAG_HPP_ #define S2E_DISTURBANCES_AIR_DRAG_HPP_ -#include #include #include "../environment/local/atmosphere.hpp" From e91e49438f6b4465fa9b5819487a2370a7ef7fb4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:45:00 +0100 Subject: [PATCH 0429/1086] Delete pragma once --- src/disturbances/air_drag.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 8add4bbbd..2b14ecc1f 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -13,7 +13,6 @@ #include "../library/math/vector.hpp" #include "surface_force.hpp" -#pragma once /** * @class AirDrag * @brief Class to calculate the air drag disturbance force and torque From 4b060fe0b6676188a8e6367a7278933523414a26 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:45:42 +0100 Subject: [PATCH 0430/1086] Fix comments --- src/disturbances/air_drag.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 2b14ecc1f..cd2c30471 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -74,12 +74,12 @@ class AirDrag : public SurfaceForce { */ void CalCnCt(libra::Vector<3>& velocity_b_m_s); /** - * @fn funcPi + * @fn CalcFuncPi * @brief Calculate The Pi function in the algorithm */ double CalcFuncPi(double s); /** - * @fn funcChi + * @fn CalcFuncChi * @brief Calculate The Chi function in the algorithm */ double CalcFuncChi(double s); From 221799e0c8dba44accdee3a47db56ad5506615fc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:53:39 +0100 Subject: [PATCH 0431/1086] Fix local variables name --- src/disturbances/air_drag.cpp | 32 +++++++++++++++++--------------- src/disturbances/air_drag.hpp | 22 +++++++++++----------- 2 files changed, 28 insertions(+), 26 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 26442befa..706a7be79 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -11,15 +11,15 @@ #include "../interface/log_output/log_utility.hpp" -AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_degC, - const double molecular_temperature_degC, const double molecular_weight, const bool is_calculation_enabled) - : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) { +AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, + const double molecular_temperature_K, const double molecular_weight_g_mol, const bool is_calculation_enabled) + : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled), + wall_temperature_K_(wall_temperature_K), + molecular_temperature_K_(molecular_temperature_K), + molecular_weight_g_mol_(molecular_weight_g_mol) { int num = surfaces_.size(); - Ct_.assign(num, 1.0); - Cn_.assign(num, 0.0); - Tw_ = wall_temperature_degC; - Tm_ = molecular_temperature_degC; - M_ = molecular_weight; + ct_.assign(num, 1.0); + cn_.assign(num, 0.0); } void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { @@ -34,8 +34,8 @@ void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens CalCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { double k = 0.5 * rho_kg_m3_ * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); - normal_coefficients_[i] = k * Cn_[i]; - tangential_coefficients_[i] = k * Ct_[i]; + normal_coefficients_[i] = k * cn_[i]; + tangential_coefficients_[i] = k * ct_[i]; } } @@ -57,14 +57,16 @@ void AirDrag::CalCnCt(Vector<3>& velocity_b_m_s) { double velocity_norm_m_s = norm(velocity_b_m_s); // Re-emitting speed - double S = sqrt(M_ * velocity_norm_m_s * velocity_norm_m_s / (2.0 * environment::boltzmann_constant_J_K * Tw_)); + double speed = + sqrt(molecular_weight_g_mol_ * velocity_norm_m_s * velocity_norm_m_s / (2.0 * environment::boltzmann_constant_J_K * wall_temperature_K_)); // CalcTheta(vel_b); for (size_t i = 0; i < surfaces_.size(); i++) { - double Sn = S * cos_theta_[i]; - double St = S * sin_theta_[i]; + double speed_n = speed * cos_theta_[i]; + double speed_t = speed * sin_theta_[i]; double diffuse = 1.0 - surfaces_[i].GetAirSpecularity(); - Cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * CalcFuncPi(Sn) / (S * S) + diffuse / 2.0 * CalcFuncChi(Sn) / (S * S) * sqrt(Tw_ / Tm_); - Ct_[i] = diffuse * St * CalcFuncChi(Sn) / (sqrt(libra::pi) * S * S); + cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * CalcFuncPi(speed_n) / (speed * speed) + + diffuse / 2.0 * CalcFuncChi(speed_n) / (speed * speed) * sqrt(wall_temperature_K_ / molecular_temperature_K_); + ct_[i] = diffuse * speed_t * CalcFuncChi(speed_n) / (sqrt(libra::pi) * speed * speed); } } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index cd2c30471..f9fe80b6f 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -24,13 +24,13 @@ class AirDrag : public SurfaceForce { * @brief Constructor * @param [in] surfaces: Surface information of the spacecraft * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] - * @param [in] wall_temperature_degC: Temperature of surfaces [degC] - * @param [in] molecular_temperature_degC: Temperature of air molecular [degC] - * @param [in] molecular_weight: Molecular weight + * @param [in] wall_temperature_K: Temperature of surfaces [K] + * @param [in] molecular_temperature_K: Temperature of air molecular [K] + * @param [in] molecular_weight_g_mol: Molecular weight [g/mol] * @param [in] is_calculation_enabled: Calculation flag */ - AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_degC, - const double molecular_temperature_degC, const double molecular_weight, const bool is_calculation_enabled = true); + AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, + const double molecular_temperature_K, const double molecular_weight_g_mol, const bool is_calculation_enabled = true); /** * @fn Update @@ -51,12 +51,12 @@ class AirDrag : public SurfaceForce { virtual std::string GetLogValue() const; private: - vector Cn_; //!< Coefficients for out-plane force - vector Ct_; //!< Coefficients for in-plane force - double rho_kg_m3_; //!< Air density [kg/m^3] - double Tw_; //!< Temperature of surface [K] - double Tm_; //!< Temperature of atmosphere [K] - double M_; //!< Molecular weight [g/mol] + vector cn_; //!< Coefficients for out-plane force + vector ct_; //!< Coefficients for in-plane force + double rho_kg_m3_; //!< Air density [kg/m^3] + double wall_temperature_K_; //!< Temperature of surface [K] + double molecular_temperature_K_; //!< Temperature of atmosphere [K] + double molecular_weight_g_mol_; //!< Molecular weight [g/mol] /** * @fn CalcCoefficients From c0bb54e9b0c4484ecb5bfc449ea7a6e4306eae78 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 13:56:44 +0100 Subject: [PATCH 0432/1086] Fix 0 to 0.0 --- src/disturbances/disturbances.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index e7e751a3f..c2f1ddccc 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -95,8 +95,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const } void Disturbances::InitializeForceAndTorque() { - sum_torque_ = Vector<3>(0); - sum_force_ = Vector<3>(0); + sum_torque_ = Vector<3>(0.0); + sum_force_ = Vector<3>(0.0); } -void Disturbances::InitializeAcceleration() { sum_acceleration_i_ = Vector<3>(0); } +void Disturbances::InitializeAcceleration() { sum_acceleration_i_ = Vector<3>(0.0); } From 9e6de8597bcc451a5bfc98a46736d36b02e0cc38 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:03:26 +0100 Subject: [PATCH 0433/1086] Fix private member name --- src/disturbances/disturbances.cpp | 23 +++++++++++------------ src/disturbances/disturbances.hpp | 9 +++++---- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index c2f1ddccc..d082d0f7a 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -37,8 +37,8 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn InitializeForceAndTorque(); for (auto dist : disturbances_) { dist->UpdateIfEnabled(local_env, dynamics); - sum_torque_ += dist->GetTorque_b_Nm(); - sum_force_ += dist->GetForce_b_N(); + total_torque_b_Nm_ += dist->GetTorque_b_Nm(); + total_force_b_N_ += dist->GetForce_b_N(); } } // Update disturbances that depend only on the position @@ -46,7 +46,7 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn InitializeAcceleration(); for (auto acc_dist : acc_disturbances_) { acc_dist->UpdateIfEnabled(local_env, dynamics); - sum_acceleration_i_ += acc_dist->GetAcceleration_i_m_s2(); + total_acceleration_i_m_s2_ += acc_dist->GetAcceleration_i_m_s2(); } } } @@ -58,15 +58,14 @@ void Disturbances::LogSetup(Logger& logger) { for (auto acc_dist : acc_disturbances_) { logger.AddLoggable(acc_dist); } - // Log ini file logger.CopyFileToLogDir(ini_fname_); } -Vector<3> Disturbances::GetTorque() { return sum_torque_; } +Vector<3> Disturbances::GetTorque() { return total_torque_b_Nm_; } -Vector<3> Disturbances::GetForce() { return sum_force_; } +Vector<3> Disturbances::GetForce() { return total_force_b_N_; } -Vector<3> Disturbances::GetAccelerationI() { return sum_acceleration_i_; } +Vector<3> Disturbances::GetAccelerationI() { return total_acceleration_i_m_s2_; } void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { @@ -79,8 +78,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const SolarRadiation* srp_dist = new SolarRadiation(InitSRDist(ini_fname_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_.push_back(srp_dist); - ThirdBodyGravity* thirdbodygravity = new ThirdBodyGravity(InitThirdBodyGravity(ini_fname_, sim_config->ini_base_fname_)); - acc_disturbances_.push_back(thirdbodygravity); + ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(ini_fname_, sim_config->ini_base_fname_)); + acc_disturbances_.push_back(third_body_gravity); if (glo_env->GetCelesInfo().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) @@ -95,8 +94,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const } void Disturbances::InitializeForceAndTorque() { - sum_torque_ = Vector<3>(0.0); - sum_force_ = Vector<3>(0.0); + total_torque_b_Nm_ = Vector<3>(0.0); + total_force_b_N_ = Vector<3>(0.0); } -void Disturbances::InitializeAcceleration() { sum_acceleration_i_ = Vector<3>(0.0); } +void Disturbances::InitializeAcceleration() { total_acceleration_i_m_s2_ = Vector<3>(0.0); } diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 5985461ff..ca69b8298 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -62,11 +62,12 @@ class Disturbances { private: std::string ini_fname_; //!< Initialization file name - std::vector disturbances_; //!< List of disturbances - Vector<3> sum_torque_; //!< Total disturbance torque in the body frame [Nm] - Vector<3> sum_force_; //!< Total disturbance force in the body frame [N] + std::vector disturbances_; //!< List of disturbances + Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] + Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] + vector acc_disturbances_; //!< List of acceleration disturbances - Vector<3> sum_acceleration_i_; //!< Total disturbance acceleration in the inertial frame [m/s2] + Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] /** * @fn InitializeInstances From e09a1e6943e567e988126ab4403dc706e120ae10 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:06:55 +0100 Subject: [PATCH 0434/1086] Move to inline function --- src/disturbances/disturbances.cpp | 30 ++++++++++++------------------ src/disturbances/disturbances.hpp | 18 ++++++++++-------- 2 files changed, 22 insertions(+), 26 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index d082d0f7a..a844703be 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -22,11 +22,11 @@ Disturbances::Disturbances(const SimulationConfig* sim_config, const int sat_id, } Disturbances::~Disturbances() { - for (auto dist : disturbances_) { + for (auto dist : disturbances_list_) { delete dist; } - for (auto acc_dist : acc_disturbances_) { + for (auto acc_dist : acceleration_disturbances_list_) { delete acc_dist; } } @@ -35,7 +35,7 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn // Update disturbances that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { InitializeForceAndTorque(); - for (auto dist : disturbances_) { + for (auto dist : disturbances_list_) { dist->UpdateIfEnabled(local_env, dynamics); total_torque_b_Nm_ += dist->GetTorque_b_Nm(); total_force_b_N_ += dist->GetForce_b_N(); @@ -44,7 +44,7 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn // Update disturbances that depend only on the position if (sim_time->GetOrbitPropagateFlag()) { InitializeAcceleration(); - for (auto acc_dist : acc_disturbances_) { + for (auto acc_dist : acceleration_disturbances_list_) { acc_dist->UpdateIfEnabled(local_env, dynamics); total_acceleration_i_m_s2_ += acc_dist->GetAcceleration_i_m_s2(); } @@ -52,45 +52,39 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn } void Disturbances::LogSetup(Logger& logger) { - for (auto dist : disturbances_) { + for (auto dist : disturbances_list_) { logger.AddLoggable(dist); } - for (auto acc_dist : acc_disturbances_) { + for (auto acc_dist : acceleration_disturbances_list_) { logger.AddLoggable(acc_dist); } logger.CopyFileToLogDir(ini_fname_); } -Vector<3> Disturbances::GetTorque() { return total_torque_b_Nm_; } - -Vector<3> Disturbances::GetForce() { return total_force_b_N_; } - -Vector<3> Disturbances::GetAccelerationI() { return total_acceleration_i_m_s2_; } - void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); ini_fname_ = iniAccess.ReadString("SETTING_FILES", "disturbance_file"); GravityGradient* gg_dist = new GravityGradient(InitGravityGradient(ini_fname_, glo_env->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); - disturbances_.push_back(gg_dist); + disturbances_list_.push_back(gg_dist); SolarRadiation* srp_dist = new SolarRadiation(InitSRDist(ini_fname_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); - disturbances_.push_back(srp_dist); + disturbances_list_.push_back(srp_dist); ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(ini_fname_, sim_config->ini_base_fname_)); - acc_disturbances_.push_back(third_body_gravity); + acceleration_disturbances_list_.push_back(third_body_gravity); if (glo_env->GetCelesInfo().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) AirDrag* air_dist = new AirDrag(InitAirDrag(ini_fname_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); - disturbances_.push_back(air_dist); + disturbances_list_.push_back(air_dist); MagDisturbance* mag_dist = new MagDisturbance(InitMagDisturbance(ini_fname_, structure->GetRMMParams())); - disturbances_.push_back(mag_dist); + disturbances_list_.push_back(mag_dist); GeoPotential* geopotential = new GeoPotential(InitGeoPotential(ini_fname_)); - acc_disturbances_.push_back(geopotential); + acceleration_disturbances_list_.push_back(geopotential); } void Disturbances::InitializeForceAndTorque() { diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index ca69b8298..deca39480 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -47,27 +47,29 @@ class Disturbances { * @fn GetTorque * @brief Return total disturbance torque in the body frame [Nm] */ - Vector<3> GetTorque(); + inline libra::Vector<3> GetTorque() { return total_torque_b_Nm_; } + /** * @fn GetTorque * @brief Return total disturbance force in the body frame [N] */ - Vector<3> GetForce(); + inline libra::Vector<3> GetForce() { return total_force_b_N_; } + /** * @fn GetTorque * @brief Return total disturbance acceleration in the inertial frame [m/s2] */ - Vector<3> GetAccelerationI(); + inline libra::Vector<3> GetAccelerationI() { return total_acceleration_i_m_s2_; } private: std::string ini_fname_; //!< Initialization file name - std::vector disturbances_; //!< List of disturbances - Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] - Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] + std::vector disturbances_list_; //!< List of disturbances + Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] + Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] - vector acc_disturbances_; //!< List of acceleration disturbances - Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] + vector acceleration_disturbances_list_; //!< List of acceleration disturbances + Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] /** * @fn InitializeInstances From d06832f13013951549357c3c682a40ff6f5247f1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:14:42 +0100 Subject: [PATCH 0435/1086] Fix function argument name --- src/disturbances/disturbances.cpp | 30 ++++++++++++++++-------------- src/disturbances/disturbances.hpp | 6 +++--- 2 files changed, 19 insertions(+), 17 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index a844703be..a30b88f43 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -31,12 +31,12 @@ Disturbances::~Disturbances() { } } -void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dynamics, const SimTime* sim_time) { +void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimTime* sim_time) { // Update disturbances that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { InitializeForceAndTorque(); for (auto dist : disturbances_list_) { - dist->UpdateIfEnabled(local_env, dynamics); + dist->UpdateIfEnabled(local_environment, dynamics); total_torque_b_Nm_ += dist->GetTorque_b_Nm(); total_force_b_N_ += dist->GetForce_b_N(); } @@ -45,7 +45,7 @@ void Disturbances::Update(const LocalEnvironment& local_env, const Dynamics& dyn if (sim_time->GetOrbitPropagateFlag()) { InitializeAcceleration(); for (auto acc_dist : acceleration_disturbances_list_) { - acc_dist->UpdateIfEnabled(local_env, dynamics); + acc_dist->UpdateIfEnabled(local_environment, dynamics); total_acceleration_i_m_s2_ += acc_dist->GetAcceleration_i_m_s2(); } } @@ -58,32 +58,34 @@ void Disturbances::LogSetup(Logger& logger) { for (auto acc_dist : acceleration_disturbances_list_) { logger.AddLoggable(acc_dist); } - logger.CopyFileToLogDir(ini_fname_); + logger.CopyFileToLogDir(initialize_file_name_); } void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, - const GlobalEnvironment* glo_env) { - IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); - ini_fname_ = iniAccess.ReadString("SETTING_FILES", "disturbance_file"); + const GlobalEnvironment* global_environment) { + IniAccess ini_access = IniAccess(sim_config->sat_file_[sat_id]); + initialize_file_name_ = ini_access.ReadString("SETTING_FILES", "disturbance_file"); - GravityGradient* gg_dist = new GravityGradient(InitGravityGradient(ini_fname_, glo_env->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); + GravityGradient* gg_dist = + new GravityGradient(InitGravityGradient(initialize_file_name_, global_environment->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); disturbances_list_.push_back(gg_dist); - SolarRadiation* srp_dist = new SolarRadiation(InitSRDist(ini_fname_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); + SolarRadiation* srp_dist = + new SolarRadiation(InitSRDist(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(srp_dist); - ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(ini_fname_, sim_config->ini_base_fname_)); + ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->ini_base_fname_)); acceleration_disturbances_list_.push_back(third_body_gravity); - if (glo_env->GetCelesInfo().GetCenterBodyName() != "EARTH") return; + if (global_environment->GetCelesInfo().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) - AirDrag* air_dist = new AirDrag(InitAirDrag(ini_fname_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); + AirDrag* air_dist = new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(air_dist); - MagDisturbance* mag_dist = new MagDisturbance(InitMagDisturbance(ini_fname_, structure->GetRMMParams())); + MagDisturbance* mag_dist = new MagDisturbance(InitMagDisturbance(initialize_file_name_, structure->GetRMMParams())); disturbances_list_.push_back(mag_dist); - GeoPotential* geopotential = new GeoPotential(InitGeoPotential(ini_fname_)); + GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); acceleration_disturbances_list_.push_back(geopotential); } diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index deca39480..62f432061 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -25,7 +25,7 @@ class Disturbances { * @fn Disturbances * @brief Constructor */ - Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env); + Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* global_environment); /** * @fn ~Disturbances * @brief Destructor @@ -36,7 +36,7 @@ class Disturbances { * @fn Update * @brief Update all disturbance calculation */ - void Update(const LocalEnvironment& local_env, const Dynamics& dynamics, const SimTime* sim_time); + void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimTime* sim_time); /** * @fn LogSetup * @brief log setup for all disturbances @@ -62,7 +62,7 @@ class Disturbances { inline libra::Vector<3> GetAccelerationI() { return total_acceleration_i_m_s2_; } private: - std::string ini_fname_; //!< Initialization file name + std::string initialize_file_name_; //!< Initialization file name std::vector disturbances_list_; //!< List of disturbances Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] From 5819be06cbce17c66c3dde7614f92c6d7306cb2f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:16:14 +0100 Subject: [PATCH 0436/1086] Add unit into function name --- src/disturbances/disturbances.hpp | 6 +++--- src/simulation/spacecraft/spacecraft.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 62f432061..2bb894c53 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -47,19 +47,19 @@ class Disturbances { * @fn GetTorque * @brief Return total disturbance torque in the body frame [Nm] */ - inline libra::Vector<3> GetTorque() { return total_torque_b_Nm_; } + inline libra::Vector<3> GetTorque_b_Nm() { return total_torque_b_Nm_; } /** * @fn GetTorque * @brief Return total disturbance force in the body frame [N] */ - inline libra::Vector<3> GetForce() { return total_force_b_N_; } + inline libra::Vector<3> GetForce_b_N() { return total_force_b_N_; } /** * @fn GetTorque * @brief Return total disturbance acceleration in the inertial frame [m/s2] */ - inline libra::Vector<3> GetAccelerationI() { return total_acceleration_i_m_s2_; } + inline libra::Vector<3> GetAcceleration_i_m_s2() { return total_acceleration_i_m_s2_; } private: std::string initialize_file_name_; //!< Initialization file name diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 35837bf0f..cb2521957 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -71,9 +71,9 @@ void Spacecraft::Update(const SimTime* sim_time) { clock_gen_.UpdateComponents(sim_time); // Add generated force and torque by disturbances - dynamics_->AddAcceleration_i(disturbances_->GetAccelerationI()); - dynamics_->AddTorque_b(disturbances_->GetTorque()); - dynamics_->AddForce_b(disturbances_->GetForce()); + dynamics_->AddAcceleration_i(disturbances_->GetAcceleration_i_m_s2()); + dynamics_->AddTorque_b(disturbances_->GetTorque_b_Nm()); + dynamics_->AddForce_b(disturbances_->GetForce_b_N()); // Add generated force and torque by components dynamics_->AddTorque_b(components_->GenerateTorque_Nm_b()); From ff91598aefebd887b5957481dac57755696210fb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:20:36 +0100 Subject: [PATCH 0437/1086] Fix comments --- src/disturbances/disturbances.hpp | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 2bb894c53..d4cbca07b 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -24,6 +24,10 @@ class Disturbances { /** * @fn Disturbances * @brief Constructor + * @param [in] sim_config: Simulation Configuration + * @param [in] sat_id: Satellite ID + * @param [in] structure: Structure information of spacecraft + * @param [in] global_environment: Global environment information */ Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* global_environment); /** @@ -35,11 +39,15 @@ class Disturbances { /** * @fn Update * @brief Update all disturbance calculation + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information + * @param [in] sim_time: Simulation time */ void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimTime* sim_time); /** * @fn LogSetup * @brief log setup for all disturbances + * @param [in] logger: Logger */ void LogSetup(Logger& logger); @@ -74,8 +82,13 @@ class Disturbances { /** * @fn InitializeInstances * @brief Initialize all disturbance class + * @param [in] sim_config: Simulation Configuration + * @param [in] sat_id: Satellite ID + * @param [in] structure: Structure information of spacecraft + * @param [in] global_environment: Global environment information */ - void InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env); + void InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, + const GlobalEnvironment* global_environment); /** * @fn InitializeForceAndTorque * @brief Initialize disturbance force and torque From 5dcf49a9a3e491b0d65639d8e8cd5beddd206535 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:23:53 +0100 Subject: [PATCH 0438/1086] Remove using --- src/disturbances/geopotential.cpp | 34 +++++++++++++++---------------- src/disturbances/geopotential.hpp | 7 ++----- 2 files changed, 18 insertions(+), 23 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index b29793c66..e44d1570c 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -15,19 +15,17 @@ // #define DEBUG_GEOPOTENTIAL -using namespace std; - -GeoPotential::GeoPotential(const int degree, const string file_path, const bool is_calculation_enabled) +GeoPotential::GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled) : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize - acc_ecef_ = Vector<3>(0); - debug_pos_ecef_ = Vector<3>(0); + acc_ecef_ = libra::Vector<3>(0); + debug_pos_ecef_ = libra::Vector<3>(0); // degree if (degree_ > 360) { degree_ = 360; - cout << "Inputted degree of GeoPotential is too large for EGM96 " - "model(limit is 360)\n"; - cout << "degree of GeoPotential set as " << degree_ << "\n"; + std::cout << "Inputted degree of GeoPotential is too large for EGM96 " + "model(limit is 360)\n"; + std::cout << "degree of GeoPotential set as " << degree_ << "\n"; } else if (degree_ <= 1) { degree_ = 0; } @@ -40,15 +38,15 @@ GeoPotential::GeoPotential(const int degree, const string file_path, const bool if (degree_ >= 2) { if (!ReadCoefficientsEGM96(file_path)) { degree_ = 0; - cout << "degree of GeoPotential set as " << degree_ << "\n"; + std::cout << "degree of GeoPotential set as " << degree_ << "\n"; } } } -bool GeoPotential::ReadCoefficientsEGM96(string file_name) { - ifstream coeff_file(file_name); +bool GeoPotential::ReadCoefficientsEGM96(std::string file_name) { + std::ifstream coeff_file(file_name); if (!coeff_file.is_open()) { - cerr << "file open error:Geopotential\n"; + std::cerr << "file open error:Geopotential\n"; return false; } @@ -56,9 +54,9 @@ bool GeoPotential::ReadCoefficientsEGM96(string file_name) { for (int i = 0; i < num_coeff; i++) { int n_, m_; double c_nm_norm, s_nm_norm; - string line; + std::string line; getline(coeff_file, line); - istringstream streamline(line); + std::istringstream streamline(line); streamline >> n_ >> m_ >> c_nm_norm >> s_nm_norm; c_[n_][m_] = c_nm_norm; @@ -189,8 +187,8 @@ void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev return; } -string GeoPotential::GetLogHeader() const { - string str_tmp = ""; +std::string GeoPotential::GetLogHeader() const { + std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL str_tmp += WriteVector("pos_", "ecef", "m", 3); @@ -201,8 +199,8 @@ string GeoPotential::GetLogHeader() const { return str_tmp; } -string GeoPotential::GetLogValue() const { - string str_tmp = ""; +std::string GeoPotential::GetLogValue() const { + std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL str_tmp += WriteVector(debug_pos_ecef_, 15); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 654c9983b..ee3c11c36 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -14,9 +14,6 @@ #include "../library/math/vector.hpp" #include "acceleration_disturbance.hpp" -using libra::Matrix; -using libra::Vector; - /** * @class GeoPotential * @brief Class to calculate the high-order earth gravity acceleration @@ -84,8 +81,8 @@ class GeoPotential : public AccelerationDisturbance { void v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2); // debug - Vector<3> debug_pos_ecef_; //!< Spacecraft position in ECEF frame [m] - double time_ = 0.0; //!< Calculation time [ms] + libra::Vector<3> debug_pos_ecef_; //!< Spacecraft position in ECEF frame [m] + double time_ = 0.0; //!< Calculation time [ms] }; #endif // S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ From 4253c569dabf2d01d1fcca8dd1a5f2ea66e1e944 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:25:13 +0100 Subject: [PATCH 0439/1086] Add unit --- src/disturbances/geopotential.cpp | 6 +++--- src/disturbances/geopotential.hpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index e44d1570c..6ffe20ea2 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -19,7 +19,7 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize acc_ecef_ = libra::Vector<3>(0); - debug_pos_ecef_ = libra::Vector<3>(0); + debug_pos_ecef_m_ = libra::Vector<3>(0); // degree if (degree_ > 360) { degree_ = 360; @@ -69,7 +69,7 @@ void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dyn #ifdef DEBUG_GEOPOTENTIAL chrono::system_clock::time_point start, end; start = chrono::system_clock::now(); - debug_pos_ecef_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); + debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); #endif CalcAccelerationECEF(dynamics.GetOrbit().GetSatPosition_ecef()); @@ -203,7 +203,7 @@ std::string GeoPotential::GetLogValue() const { std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL - str_tmp += WriteVector(debug_pos_ecef_, 15); + str_tmp += WriteVector(debug_pos_ecef_m_, 15); str_tmp += WriteScalar(time_); #endif diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index ee3c11c36..0e8b3a73b 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -81,8 +81,8 @@ class GeoPotential : public AccelerationDisturbance { void v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2); // debug - libra::Vector<3> debug_pos_ecef_; //!< Spacecraft position in ECEF frame [m] - double time_ = 0.0; //!< Calculation time [ms] + libra::Vector<3> debug_pos_ecef_m_; //!< Spacecraft position in ECEF frame [m] + double time_ = 0.0; //!< Calculation time [ms] }; #endif // S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ From a26a71287dfba7d2c6bdadf4b7cab0ca486092af Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:27:27 +0100 Subject: [PATCH 0440/1086] Fix 0 to 0.0 --- src/disturbances/geopotential.cpp | 12 ++++++------ src/disturbances/geopotential.hpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 6ffe20ea2..e2d8774f9 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -18,8 +18,8 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled) : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize - acc_ecef_ = libra::Vector<3>(0); - debug_pos_ecef_m_ = libra::Vector<3>(0); + acc_ecef_ = libra::Vector<3>(0.0); + debug_pos_ecef_m_ = libra::Vector<3>(0.0); // degree if (degree_ > 360) { degree_ = 360; @@ -67,7 +67,7 @@ bool GeoPotential::ReadCoefficientsEGM96(std::string file_name) { void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dynamics) { #ifdef DEBUG_GEOPOTENTIAL - chrono::system_clock::time_point start, end; + chrono::system_clock::time_ms_point start, end; start = chrono::system_clock::now(); debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); #endif @@ -75,7 +75,7 @@ void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dyn CalcAccelerationECEF(dynamics.GetOrbit().GetSatPosition_ecef()); #ifdef DEBUG_GEOPOTENTIAL end = chrono::system_clock::now(); - time_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); + time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif Matrix<3, 3> trans_eci2ecef_ = local_env.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); @@ -192,7 +192,7 @@ std::string GeoPotential::GetLogHeader() const { #ifdef DEBUG_GEOPOTENTIAL str_tmp += WriteVector("pos_", "ecef", "m", 3); - str_tmp += WriteScalar("time_geop", "ms"); + str_tmp += WriteScalar("time_ms_geop", "ms"); #endif str_tmp += WriteVector("geopotential_acceleration", "ecef", "m/s2", 3); @@ -204,7 +204,7 @@ std::string GeoPotential::GetLogValue() const { #ifdef DEBUG_GEOPOTENTIAL str_tmp += WriteVector(debug_pos_ecef_m_, 15); - str_tmp += WriteScalar(time_); + str_tmp += WriteScalar(time_ms_); #endif str_tmp += WriteVector(acc_ecef_, 15); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 0e8b3a73b..ee1292977 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -82,7 +82,7 @@ class GeoPotential : public AccelerationDisturbance { // debug libra::Vector<3> debug_pos_ecef_m_; //!< Spacecraft position in ECEF frame [m] - double time_ = 0.0; //!< Calculation time [ms] + double time_ms_ = 0.0; //!< Calculation time [ms] }; #endif // S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ From d1881a2a0cf251122dc76310fe02d23cad480f22 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:30:41 +0100 Subject: [PATCH 0441/1086] Fix argument name --- src/disturbances/geopotential.cpp | 8 ++++---- src/disturbances/geopotential.hpp | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index e2d8774f9..62471463c 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -65,7 +65,7 @@ bool GeoPotential::ReadCoefficientsEGM96(std::string file_name) { return true; } -void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dynamics) { +void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynamics &dynamics) { #ifdef DEBUG_GEOPOTENTIAL chrono::system_clock::time_ms_point start, end; start = chrono::system_clock::now(); @@ -78,13 +78,13 @@ void GeoPotential::Update(const LocalEnvironment &local_env, const Dynamics &dyn time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif - Matrix<3, 3> trans_eci2ecef_ = local_env.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); + Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acc_ecef_; } -void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef) { - x = position_ecef[0], y = position_ecef[1], z = position_ecef[2]; +void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { + x = position_ecef_m[0], y = position_ecef_m[1], z = position_ecef_m[2]; r = sqrt(x * x + y * y + z * z); // Calc V and W diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index ee1292977..a7c4e5b6a 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -31,7 +31,7 @@ class GeoPotential : public AccelerationDisturbance { * @fn Update * @brief Override Updates function of SimpleDisturbance */ - virtual void Update(const LocalEnvironment &local_env, const Dynamics &dynamics); + virtual void Update(const LocalEnvironment &local_environment, const Dynamics &dynamics); // Override ILoggable /** @@ -48,9 +48,9 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn CalcAccelerationECEF * @brief Calculate the high-order earth gravity in the ECEF frame - * @param [in] position_ecef: Position of the spacecraft in the ECEF fram [m] + * @param [in] position_ecef_m: Position of the spacecraft in the ECEF fram [m] */ - void CalcAccelerationECEF(const Vector<3> &position_ecef); + void CalcAccelerationECEF(const Vector<3> &position_ecef_m); /** * @fn ReadCoefficientsEGM96 From 2347c3290bf6c654beaa4f19a72a521f67fa0e06 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:40:09 +0100 Subject: [PATCH 0442/1086] Fix argument name --- .../initialize_files/sample_disturbance.ini | 2 +- src/disturbances/geopotential.cpp | 43 ++++++++++--------- src/disturbances/geopotential.hpp | 30 +++++++------ 3 files changed, 39 insertions(+), 36 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index 2a46ae623..c99764428 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -1,6 +1,6 @@ [GEOPOTENTIAL] // Enable only when the center object is defined as the Earth -calculation = DISABLE +calculation = ENABLE logging = ENABLE degree = 4 coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 62471463c..63afade9d 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -18,7 +18,7 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled) : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize - acc_ecef_ = libra::Vector<3>(0.0); + acceleration_ecef_m_s2_ = libra::Vector<3>(0.0); debug_pos_ecef_m_ = libra::Vector<3>(0.0); // degree if (degree_ > 360) { @@ -80,19 +80,19 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); - acceleration_i_m_s2_ = trans_ecef2eci * acc_ecef_; + acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { - x = position_ecef_m[0], y = position_ecef_m[1], z = position_ecef_m[2]; - r = sqrt(x * x + y * y + z * z); + ecef_x_m_ = position_ecef_m[0], ecef_y_m_ = position_ecef_m[1], ecef_z_m_ = position_ecef_m[2]; + radius_m_ = sqrt(ecef_x_m_ * ecef_x_m_ + ecef_y_m_ * ecef_y_m_ + ecef_z_m_ * ecef_z_m_); // Calc V and W int degree_vw = degree_ + 1; vector> v(degree_vw + 1, vector(degree_vw + 1, 0.0)); vector> w(degree_vw + 1, vector(degree_vw + 1, 0.0)); // n=m=0 - v[0][0] = environment::earth_equatorial_radius_m / r; + v[0][0] = environment::earth_equatorial_radius_m / radius_m_; w[0][0] = 0.0; m = 0; @@ -110,7 +110,7 @@ void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { } // Calc Acceleration - acc_ecef_ *= 0.0; + acceleration_ecef_m_s2_ *= 0.0; for (n = 0; n <= degree_; n++) // this loop can integrate with previous loop { m = 0; @@ -118,9 +118,9 @@ void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { double normalize = sqrt((2.0 * n_d + 1.0) / (2.0 * n_d + 3.0)); double normalize_xy = normalize * sqrt((n_d + 2.0) * (n_d + 1.0) / 2.0); // m==0 - acc_ecef_[0] += -c_[n][0] * v[n + 1][1] * normalize_xy; - acc_ecef_[1] += -c_[n][0] * w[n + 1][1] * normalize_xy; - acc_ecef_[2] += (n + 1.0) * (-c_[n][0] * v[n + 1][0] - s_[n][0] * w[n + 1][0]) * normalize; + acceleration_ecef_m_s2_[0] += -c_[n][0] * v[n + 1][1] * normalize_xy; + acceleration_ecef_m_s2_[1] += -c_[n][0] * w[n + 1][1] * normalize_xy; + acceleration_ecef_m_s2_[2] += (n + 1.0) * (-c_[n][0] * v[n + 1][0] - s_[n][0] * w[n + 1][0]) * normalize; for (m = 1; m <= n; m++) { double m_d = (double)m; double factorial = (n_d - m_d + 1.0) * (n_d - m_d + 2.0); @@ -132,14 +132,15 @@ void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { normalize_xy2 = normalize * sqrt(factorial); double normalize_z = normalize * sqrt((n_d + m_d + 1.0) / (n_d - m_d + 1.0)); - acc_ecef_[0] += 0.5 * (normalize_xy1 * (-c_[n][m] * v[n + 1][m + 1] - s_[n][m] * w[n + 1][m + 1]) + - normalize_xy2 * (c_[n][m] * v[n + 1][m - 1] + s_[n][m] * w[n + 1][m - 1])); - acc_ecef_[1] += 0.5 * (normalize_xy1 * (-c_[n][m] * w[n + 1][m + 1] + s_[n][m] * v[n + 1][m + 1]) + - normalize_xy2 * (-c_[n][m] * w[n + 1][m - 1] + s_[n][m] * v[n + 1][m - 1])); - acc_ecef_[2] += (n_d - m_d + 1.0) * (-c_[n][m] * v[n + 1][m] - s_[n][m] * w[n + 1][m]) * normalize_z; + acceleration_ecef_m_s2_[0] += 0.5 * (normalize_xy1 * (-c_[n][m] * v[n + 1][m + 1] - s_[n][m] * w[n + 1][m + 1]) + + normalize_xy2 * (c_[n][m] * v[n + 1][m - 1] + s_[n][m] * w[n + 1][m - 1])); + acceleration_ecef_m_s2_[1] += 0.5 * (normalize_xy1 * (-c_[n][m] * w[n + 1][m + 1] + s_[n][m] * v[n + 1][m + 1]) + + normalize_xy2 * (-c_[n][m] * w[n + 1][m - 1] + s_[n][m] * v[n + 1][m - 1])); + acceleration_ecef_m_s2_[2] += (n_d - m_d + 1.0) * (-c_[n][m] * v[n + 1][m] - s_[n][m] * w[n + 1][m]) * normalize_z; } } - acc_ecef_ *= environment::earth_gravitational_constant_m3_s2 / (environment::earth_equatorial_radius_m * environment::earth_equatorial_radius_m); + acceleration_ecef_m_s2_ *= + environment::earth_gravitational_constant_m3_s2 / (environment::earth_equatorial_radius_m * environment::earth_equatorial_radius_m); return; } @@ -149,9 +150,9 @@ void GeoPotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev double n_d = (double)n; - double tmp = environment::earth_equatorial_radius_m / (r * r); - double x_tmp = x * tmp; - double y_tmp = y * tmp; + double tmp = environment::earth_equatorial_radius_m / (radius_m_ * radius_m_); + double x_tmp = ecef_x_m_ * tmp; + double y_tmp = ecef_y_m_ * tmp; double c_normalize; if (n == 1) c_normalize = (2.0 * n_d - 1.0) * sqrt(2.0 * n_d + 1.0); @@ -169,8 +170,8 @@ void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev double m_d = (double)m; double n_d = (double)n; - double tmp = environment::earth_equatorial_radius_m / (r * r); - double z_tmp = z * tmp; + double tmp = environment::earth_equatorial_radius_m / (radius_m_ * radius_m_); + double z_tmp = ecef_z_m_ * tmp; double re_tmp = environment::earth_equatorial_radius_m * tmp; double c1 = (2.0 * n_d - 1.0) / (n_d - m_d); double c2 = (n_d + m_d - 1.0) / (n_d - m_d); @@ -207,7 +208,7 @@ std::string GeoPotential::GetLogValue() const { str_tmp += WriteScalar(time_ms_); #endif - str_tmp += WriteVector(acc_ecef_, 15); + str_tmp += WriteVector(acceleration_ecef_m_s2_, 15); return str_tmp; } diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index a7c4e5b6a..cbd52814f 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -45,6 +45,21 @@ class GeoPotential : public AccelerationDisturbance { */ virtual std::string GetLogValue() const; + private: + int degree_; //!< Maximum degree setting to calculate the geo-potential + int n = 0, m = 0; //!< Degree and order (FIXME: follow naming rule) + vector> c_; //!< Cosine coefficients + vector> s_; //!< Sine coefficients + Vector<3> acceleration_ecef_m_s2_; //!< Calculated acceleration in the ECEF frame [m/s2] + + // calculation + double radius_m_ = 0.0; //!< Radius [m] + double ecef_x_m_ = 0.0, ecef_y_m_ = 0.0, ecef_z_m_ = 0.0; //!< Spacecraft position in ECEF frame [m] + + // debug + libra::Vector<3> debug_pos_ecef_m_; //!< Spacecraft position in ECEF frame [m] + double time_ms_ = 0.0; //!< Calculation time [ms] + /** * @fn CalcAccelerationECEF * @brief Calculate the high-order earth gravity in the ECEF frame @@ -59,30 +74,17 @@ class GeoPotential : public AccelerationDisturbance { */ bool ReadCoefficientsEGM96(std::string file_name); - private: - int degree_; //!< Maximum degree setting to calculate the geo-potential - vector> c_; //!< Cosine coefficients - vector> s_; //!< Sine coefficients - Vector<3> acc_ecef_; //!< Calculated acceleration in the ECEF frame [m/s2] - // calculation - double r = 0.0; //!< Radius [m] - double x = 0.0, y = 0.0, z = 0.0; //!< Spacecraft position in ECEF frame [m] - int n = 0, m = 0; //!< Degree and order - /** * @fn v_w_nn_update * @brief Calculate V and W function for n = m */ void v_w_nn_update(double *v_nn, double *w_nn, const double v_prev, const double w_prev); + /** * @fn v_w_nm_update * @brief Calculate V and W function for n not equal m */ void v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2); - - // debug - libra::Vector<3> debug_pos_ecef_m_; //!< Spacecraft position in ECEF frame [m] - double time_ms_ = 0.0; //!< Calculation time [ms] }; #endif // S2E_DISTURBANCES_GEOPOTENTIAL_HPP_ From 7a7da2e393c1ccb14698850fc34418082c712e05 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:43:02 +0100 Subject: [PATCH 0443/1086] Remove using --- src/disturbances/gravity_gradient.cpp | 16 ++++++---------- src/disturbances/gravity_gradient.hpp | 7 +------ 2 files changed, 7 insertions(+), 16 deletions(-) diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 32a78b55f..eb651a5d7 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -7,13 +7,9 @@ #include #include -#include -#include #include "../interface/log_output/log_utility.hpp" -using namespace std; - GravityGradient::GravityGradient(const bool is_calculation_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calculation_enabled) {} @@ -25,9 +21,9 @@ void GravityGradient::Update(const LocalEnvironment& local_env, const Dynamics& dynamics.GetAttitude().GetInertiaTensor()); // TODO: use structure information to get inertia tensor } -Vector<3> GravityGradient::CalcTorque(const Vector<3> r_b_m, const Matrix<3, 3> I_b_kgm2) { +libra::Vector<3> GravityGradient::CalcTorque(const libra::Vector<3> r_b_m, const libra::Matrix<3, 3> I_b_kgm2) { double r_norm_m = norm(r_b_m); - Vector<3> u_b = r_b_m; // TODO: make undestructive normalize function for Vector + libra::Vector<3> u_b = r_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; double coeff = 3.0 * mu_m3_s2_ / pow(r_norm_m, 3.0); @@ -35,16 +31,16 @@ Vector<3> GravityGradient::CalcTorque(const Vector<3> r_b_m, const Matrix<3, 3> return torque_b_Nm_; } -string GravityGradient::GetLogHeader() const { - string str_tmp = ""; +std::string GravityGradient::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteVector("gravity_gradient_torque", "b", "Nm", 3); return str_tmp; } -string GravityGradient::GetLogValue() const { - string str_tmp = ""; +std::string GravityGradient::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteVector(torque_b_Nm_); diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index a063dd0eb..ac89e2e0f 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -6,17 +6,12 @@ #ifndef S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ #define S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ -#include - #include "../interface/log_output/loggable.hpp" #include "../library/math/matrix.hpp" #include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" #include "simple_disturbance.hpp" -using libra::Matrix; -using libra::Vector; - /** * @class GravityGradient * @brief Class to calculate the gravity gradient torque @@ -50,7 +45,7 @@ class GravityGradient : public SimpleDisturbance { * @param [in] r_b: Position vector of the earth at body frame [m] * @param [in] I_b: Inertia Tensor at body frame [kg*m^2] */ - Vector<3> CalcTorque(const Vector<3> r_b, const Matrix<3, 3> I_b); + libra::Vector<3> CalcTorque(const libra::Vector<3> r_b, const libra::Matrix<3, 3> I_b); // Override ILoggable /** From 3b6b15087bbc52e5d50f6f6f7d4d22386063ef64 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:46:50 +0100 Subject: [PATCH 0444/1086] Fix gg --- src/disturbances/gravity_gradient.cpp | 6 +++--- src/disturbances/gravity_gradient.hpp | 19 ++++++++++--------- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index eb651a5d7..98070ac03 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -16,9 +16,9 @@ GravityGradient::GravityGradient(const bool is_calculation_enabled) GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), mu_m3_s2_(mu_m3_s2) {} -void GravityGradient::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { - CalcTorque(local_env.GetCelesInfo().GetCenterBodyPosFromSC_b(), - dynamics.GetAttitude().GetInertiaTensor()); // TODO: use structure information to get inertia tensor +void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { + // TODO: use structure information to get inertia tensor + CalcTorque(local_environment.GetCelesInfo().GetCenterBodyPosFromSC_b(), dynamics.GetAttitude().GetInertiaTensor()); } libra::Vector<3> GravityGradient::CalcTorque(const libra::Vector<3> r_b_m, const libra::Matrix<3, 3> I_b_kgm2) { diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index ac89e2e0f..044c0d679 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -37,15 +37,7 @@ class GravityGradient : public SimpleDisturbance { * @fn Update * @brief Override Updates function of SimpleDisturbance */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); - - /** - * @fn CalcTorque - * @brief Calculate gravity gradient torque - * @param [in] r_b: Position vector of the earth at body frame [m] - * @param [in] I_b: Inertia Tensor at body frame [kg*m^2] - */ - libra::Vector<3> CalcTorque(const libra::Vector<3> r_b, const libra::Matrix<3, 3> I_b); + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); // Override ILoggable /** @@ -61,6 +53,15 @@ class GravityGradient : public SimpleDisturbance { private: double mu_m3_s2_; //!< Gravitational constant [m3/s2] + + /** + * @fn CalcTorque + * @brief Calculate gravity gradient torque + * @param [in] r_b_m: Position vector of the earth at body frame [m] + * @param [in] I_b_kgm2: Inertia Tensor at body frame [kg*m^2] + * @return Calculated torque at body frame [Nm] + */ + libra::Vector<3> CalcTorque(const libra::Vector<3> r_b_m, const libra::Matrix<3, 3> I_b_kgm2); }; #endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ From 56699e324bf956cbfa01030ab40a443c620724d8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:49:03 +0100 Subject: [PATCH 0445/1086] Remove using --- src/disturbances/magnetic_disturbance.cpp | 23 ++++++++++------------- src/disturbances/magnetic_disturbance.hpp | 10 +++------- 2 files changed, 13 insertions(+), 20 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 65e9b1d9c..b320c95f8 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -5,16 +5,13 @@ #include "magnetic_disturbance.hpp" -#include "../library/randomization/normal_randomization.hpp" -using libra::NormalRand; #include #include "../interface/log_output/log_utility.hpp" #include "../library/randomization/global_randomization.hpp" +#include "../library/randomization/normal_randomization.hpp" #include "../library/randomization/random_walk.hpp" -using namespace std; - MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { mag_unit_ = 1.0E-9; // [nT] -> [T] @@ -34,10 +31,10 @@ void MagDisturbance::Update(const LocalEnvironment& local_env, const Dynamics& d } void MagDisturbance::CalcRMM() { - static Vector<3> stddev(rmm_params_.GetRMMRWDev()); - static Vector<3> limit(rmm_params_.GetRMMRWLimit()); + static libra::Vector<3> stddev(rmm_params_.GetRMMRWDev()); + static libra::Vector<3> limit(rmm_params_.GetRMMRWLimit()); static RandomWalk<3> rw(0.1, stddev, limit); - static NormalRand nr(0.0, rmm_params_.GetRMMWNVar(), g_rand.MakeSeed()); + static libra::NormalRand nr(0.0, rmm_params_.GetRMMWNVar(), g_rand.MakeSeed()); rmm_b_ = rmm_params_.GetRMMConst_b(); for (int i = 0; i < 3; ++i) { @@ -47,12 +44,12 @@ void MagDisturbance::CalcRMM() { } void MagDisturbance::PrintTorque() { - cout << "MgDist_Torque_b =(" << torque_b_Nm_[0] << "," << torque_b_Nm_[1] << "," << torque_b_Nm_[2] << ") Nm"; - cout << endl; + std::cout << "MgDist_Torque_b =(" << torque_b_Nm_[0] << "," << torque_b_Nm_[1] << "," << torque_b_Nm_[2] << ") Nm"; + std::cout << std::endl; } -string MagDisturbance::GetLogHeader() const { - string str_tmp = ""; +std::string MagDisturbance::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteVector("spacecraft_magnetic_moment", "b", "Am2", 3); str_tmp += WriteVector("magnetic_disturbance_torque", "b", "Nm", 3); @@ -60,8 +57,8 @@ string MagDisturbance::GetLogHeader() const { return str_tmp; } -string MagDisturbance::GetLogValue() const { - string str_tmp = ""; +std::string MagDisturbance::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteVector(rmm_b_); str_tmp += WriteVector(torque_b_Nm_); diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index df7ef28a9..a5a70ad32 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -6,12 +6,8 @@ #ifndef S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ #define S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ -#include - -#include "../library/math/vector.hpp" -using libra::Vector; - #include "../interface/log_output/loggable.hpp" +#include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" @@ -38,7 +34,7 @@ class MagDisturbance : public SimpleDisturbance { * @brief Calculate magnetic disturbance torque * @param [in] mag_b: Magnetic field vector at the body frame [nT] */ - Vector<3> CalcTorque(const Vector<3>& mag_b); + libra::Vector<3> CalcTorque(const libra::Vector<3>& mag_b); /** * @fn Update * @brief Override Updates function of SimpleDisturbance @@ -65,7 +61,7 @@ class MagDisturbance : public SimpleDisturbance { private: double mag_unit_; //!< Constant value to change the unit [nT] -> [T] - Vector<3> rmm_b_; //!< True RMM of the spacecraft in the body frame [Am2] + libra::Vector<3> rmm_b_; //!< True RMM of the spacecraft in the body frame [Am2] const RMMParams& rmm_params_; //!< RMM parameters }; From c1e9f5a510991a2a035732835145409f1e4db1ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 14:59:02 +0100 Subject: [PATCH 0446/1086] Refactor mag disturbance --- src/disturbances/magnetic_disturbance.cpp | 32 +++++++++-------------- src/disturbances/magnetic_disturbance.hpp | 15 ++++------- 2 files changed, 18 insertions(+), 29 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index b320c95f8..2a36bf581 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -14,38 +14,32 @@ MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { - mag_unit_ = 1.0E-9; // [nT] -> [T] - rmm_b_ = rmm_params_.GetRMMConst_b(); + rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); } -Vector<3> MagDisturbance::CalcTorque(const Vector<3>& mag_b) { +Vector<3> MagDisturbance::CalcTorque(const Vector<3>& magnetic_field_b_nT) { CalcRMM(); - torque_b_Nm_ = mag_unit_ * outer_product(rmm_b_, mag_b); + torque_b_Nm_ = kMagUnit_ * outer_product(rmm_b_Am2_, magnetic_field_b_nT); return torque_b_Nm_; } -void MagDisturbance::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { +void MagDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - CalcTorque(local_env.GetMag().GetMag_b()); + CalcTorque(local_environment.GetMag().GetMag_b()); } void MagDisturbance::CalcRMM() { - static libra::Vector<3> stddev(rmm_params_.GetRMMRWDev()); - static libra::Vector<3> limit(rmm_params_.GetRMMRWLimit()); - static RandomWalk<3> rw(0.1, stddev, limit); - static libra::NormalRand nr(0.0, rmm_params_.GetRMMWNVar(), g_rand.MakeSeed()); + static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRMMRWDev()); + static libra::Vector<3> random_walk_limit(rmm_params_.GetRMMRWLimit()); + 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, rmm_params_.GetRMMWNVar(), g_rand.MakeSeed()); - rmm_b_ = rmm_params_.GetRMMConst_b(); + rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); for (int i = 0; i < 3; ++i) { - rmm_b_[i] += rw[i] + nr; + rmm_b_Am2_[i] += random_walk[i] + normal_random; } - ++rw; // Update random walk -} - -void MagDisturbance::PrintTorque() { - std::cout << "MgDist_Torque_b =(" << torque_b_Nm_[0] << "," << torque_b_Nm_[1] << "," << torque_b_Nm_[2] << ") Nm"; - std::cout << std::endl; + ++random_walk; // Update random walk } std::string MagDisturbance::GetLogHeader() const { @@ -60,7 +54,7 @@ std::string MagDisturbance::GetLogHeader() const { std::string MagDisturbance::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(rmm_b_); + str_tmp += WriteVector(rmm_b_Am2_); str_tmp += WriteVector(torque_b_Nm_); return str_tmp; diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index a5a70ad32..845dfb56e 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -32,19 +32,14 @@ class MagDisturbance : public SimpleDisturbance { /** * @fn CalcTorque * @brief Calculate magnetic disturbance torque - * @param [in] mag_b: Magnetic field vector at the body frame [nT] + * @param [in] magnetic_field_b_nT: Magnetic field vector at the body frame [nT] */ - libra::Vector<3> CalcTorque(const libra::Vector<3>& mag_b); + libra::Vector<3> CalcTorque(const libra::Vector<3>& magnetic_field_b_nT); /** * @fn Update * @brief Override Updates function of SimpleDisturbance */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); - /** - * @fn PrintTorque - * @brief Debug TODO: remove? - */ - void PrintTorque(); + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); // Override ILoggable /** @@ -59,9 +54,9 @@ class MagDisturbance : public SimpleDisturbance { virtual std::string GetLogValue() const; private: - double mag_unit_; //!< Constant value to change the unit [nT] -> [T] + const double kMagUnit_ = 1.0e-9; //!< Constant value to change the unit [nT] -> [T] - libra::Vector<3> rmm_b_; //!< True RMM of the spacecraft in the body frame [Am2] + libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] const RMMParams& rmm_params_; //!< RMM parameters }; From cb37b5b6a850afeda51bb7a2e66cfb5f7867d885 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:00:33 +0100 Subject: [PATCH 0447/1086] Refactor mag disturbance --- src/disturbances/magnetic_disturbance.hpp | 26 ++++++++++++----------- 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 845dfb56e..261c9a7bd 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -20,21 +20,11 @@ class MagDisturbance : public SimpleDisturbance { /** * @fn MagDisturbance * @brief Constructor + * @param [in] rmm_parameters: RMM parameters of the spacecraft * @param [in] is_calculation_enabled: Calculation flag */ - MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled = true); + MagDisturbance(const RMMParams& rmm_parameters, const bool is_calculation_enabled = true); - /** - * @fn CalcRMM - * @brief Calculate true RMM of the spacecraft - */ - void CalcRMM(); - /** - * @fn CalcTorque - * @brief Calculate magnetic disturbance torque - * @param [in] magnetic_field_b_nT: Magnetic field vector at the body frame [nT] - */ - libra::Vector<3> CalcTorque(const libra::Vector<3>& magnetic_field_b_nT); /** * @fn Update * @brief Override Updates function of SimpleDisturbance @@ -58,6 +48,18 @@ class MagDisturbance : public SimpleDisturbance { libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] const RMMParams& rmm_params_; //!< RMM parameters + + /** + * @fn CalcRMM + * @brief Calculate true RMM of the spacecraft + */ + void CalcRMM(); + /** + * @fn CalcTorque + * @brief Calculate magnetic disturbance torque + * @param [in] magnetic_field_b_nT: Magnetic field vector at the body frame [nT] + */ + libra::Vector<3> CalcTorque(const libra::Vector<3>& magnetic_field_b_nT); }; #endif // S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ From 00ae5373dfc550149c386d071b7904c6244b0af5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:01:48 +0100 Subject: [PATCH 0448/1086] Remove using --- src/disturbances/solar_radiation_pressure_disturbance.cpp | 6 +++--- src/disturbances/solar_radiation_pressure_disturbance.hpp | 6 ++---- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index c7f2e4bdb..7190550e4 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,17 +9,17 @@ #include "../interface/log_output/log_utility.hpp" -SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled) +SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vector<3>& cg_b, const bool is_calculation_enabled) : SurfaceForce(surfaces, cg_b, is_calculation_enabled) {} void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); - Vector<3> tmp = local_env.GetCelesInfo().GetPosFromSC_b("SUN"); + libra::Vector<3> tmp = local_env.GetCelesInfo().GetPosFromSC_b("SUN"); CalcTorqueForce(tmp, local_env.GetSrp().CalcTruePressure()); } -void SolarRadiation::CalcCoefficients(Vector<3>& input_b, double item) { +void SolarRadiation::CalcCoefficients(libra::Vector<3>& input_b, double item) { UNUSED(input_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 087a2a151..679f6a328 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -7,12 +7,10 @@ #define S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ #include -#include #include "../interface/log_output/loggable.hpp" #include "../library/math/vector.hpp" #include "surface_force.hpp" -using libra::Vector; /** * @class SolarRadiation @@ -25,7 +23,7 @@ class SolarRadiation : public SurfaceForce { * @brief Constructor * @param [in] is_calculation_enabled: Calculation flag */ - SolarRadiation(const vector& surfaces, const Vector<3>& cg_b, const bool is_calculation_enabled = true); + SolarRadiation(const std::vector& surfaces, const libra::Vector<3>& cg_b, const bool is_calculation_enabled = true); /** * @fn Update @@ -52,7 +50,7 @@ class SolarRadiation : public SurfaceForce { * @param [in] input_b: Direction vector of the sun at the body frame * @param [in] item: Solar pressure [N/m^2] */ - void CalcCoefficients(Vector<3>& input_b, double item); + void CalcCoefficients(libra::Vector<3>& input_b, double item); }; #endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ From 6f34af1f671f5a8220ea3b5ebaf1a68dcbcdcbb8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:05:12 +0100 Subject: [PATCH 0449/1086] Refactor SRP --- src/disturbances/solar_radiation_pressure_disturbance.cpp | 8 ++++---- src/disturbances/solar_radiation_pressure_disturbance.hpp | 4 +++- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 7190550e4..0da745c51 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,14 +9,14 @@ #include "../interface/log_output/log_utility.hpp" -SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vector<3>& cg_b, const bool is_calculation_enabled) - : SurfaceForce(surfaces, cg_b, is_calculation_enabled) {} +SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) + : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) {} void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); - libra::Vector<3> tmp = local_env.GetCelesInfo().GetPosFromSC_b("SUN"); - CalcTorqueForce(tmp, local_env.GetSrp().CalcTruePressure()); + libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelesInfo().GetPosFromSC_b("SUN"); + CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSrp().CalcTruePressure()); } void SolarRadiation::CalcCoefficients(libra::Vector<3>& input_b, double item) { diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 679f6a328..17b021364 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -21,9 +21,11 @@ class SolarRadiation : public SurfaceForce { /** * @fn SolarRadiation * @brief Constructor + * @param [in] surfaces: Surface information of the spacecraft + * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] * @param [in] is_calculation_enabled: Calculation flag */ - SolarRadiation(const std::vector& surfaces, const libra::Vector<3>& cg_b, const bool is_calculation_enabled = true); + SolarRadiation(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); /** * @fn Update From e0f49899a07b55fa5b448571a1469115304fa0de Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:17:19 +0100 Subject: [PATCH 0450/1086] Refactor third body --- .../initialize_files/sample_disturbance.ini | 2 +- src/disturbances/third_body_gravity.cpp | 39 ++++++++++--------- src/disturbances/third_body_gravity.hpp | 12 +++--- 3 files changed, 27 insertions(+), 26 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index c99764428..d6e87a88b 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -34,7 +34,7 @@ logging = ENABLE [THIRD_BODY_GRAVITY] -calculation = DISABLE +calculation = ENABLE logging = ENABLE // The number of gravity-generating bodies other than the central body diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index c67b1218a..0ed81d349 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -6,37 +6,38 @@ #include "third_body_gravity.hpp" ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calculation_enabled) - : AccelerationDisturbance(is_calculation_enabled), third_body_list_(third_body_list) {} + : AccelerationDisturbance(is_calculation_enabled), third_body_list_(third_body_list) { + acceleration_i_m_s2_ = libra::Vector<3>(0.0); +} ThirdBodyGravity::~ThirdBodyGravity() {} -void ThirdBodyGravity::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { - acceleration_i_m_s2_ = libra::Vector<3>(0); // initialize +void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { + acceleration_i_m_s2_ = libra::Vector<3>(0.0); // initialize - libra::Vector<3> sat_pos_i = dynamics.GetOrbit().GetSatPosition_i(); // position of the spacecraft - // from the center object + libra::Vector<3> sc_position_i_m = dynamics.GetOrbit().GetSatPosition_i(); for (auto third_body : third_body_list_) { - libra::Vector<3> third_body_pos_from_sc_i = - local_env.GetCelesInfo().GetPosFromSC_i(third_body.c_str()); // position of the third body from the spacecraft - libra::Vector<3> third_body_pos_i = sat_pos_i + third_body_pos_from_sc_i; // position of the third body - // from the center object - double gravity_constant = local_env.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); - - thirdbody_acc_i_ = CalcAcceleration(third_body_pos_i, third_body_pos_from_sc_i, gravity_constant); - acceleration_i_m_s2_ += thirdbody_acc_i_; + libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelesInfo().GetPosFromSC_i(third_body.c_str()); + libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; + double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); + + third_body_acceleration_i_m_s2_ = CalcAcceleration(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); + acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; } } -libra::Vector<3> ThirdBodyGravity::CalcAcceleration(libra::Vector<3> s, libra::Vector<3> sr, double GM) { - libra::Vector<3> acc; - double sr_norm = libra::norm(sr); - double sr_norm3 = sr_norm * sr_norm * sr_norm; +libra::Vector<3> ThirdBodyGravity::CalcAcceleration(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { + libra::Vector<3> acceleration_i_m_s2; + double s_norm = libra::norm(s); double s_norm3 = s_norm * s_norm * s_norm; - acc = GM * (1.0 / sr_norm3 * sr - 1.0 / s_norm3 * s); + double sr_norm = libra::norm(sr); + double sr_norm3 = sr_norm * sr_norm * sr_norm; + + acceleration_i_m_s2 = gravity_constant_m_s2 * (1.0 / sr_norm3 * sr - 1.0 / s_norm3 * s); - return acc; + return acceleration_i_m_s2; } std::string ThirdBodyGravity::GetLogHeader() const { diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 1ab77ce53..4d070d478 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -25,7 +25,7 @@ class ThirdBodyGravity : public AccelerationDisturbance { * @brief Constructor * @param [in] is_calculation_enabled: Calculation flag */ - ThirdBodyGravity(std::set third_body_list, const bool is_calculation_enabled = true); + ThirdBodyGravity(const std::set third_body_list, const bool is_calculation_enabled = true); /** * @fn ~ThirdBodyGravity * @brief Destructor @@ -36,9 +36,12 @@ class ThirdBodyGravity : public AccelerationDisturbance { * @fn Update * @brief Update third body disturbance */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); private: + std::set third_body_list_; //!< List of celestial bodies to calculate the third body disturbances + libra::Vector<3> third_body_acceleration_i_m_s2_{0.0}; //!< Calculated third body disturbance acceleration in the inertial frame [m/s2] + // Override classes for ILoggable /** * @fn GetLogHeader @@ -59,10 +62,7 @@ class ThirdBodyGravity : public AccelerationDisturbance { * @param [in] GM: The gravitational constants of the third celestial body [m3/s2] * @return Third body disturbance acceleration in the inertial frame in unit [m/s2] */ - libra::Vector<3> CalcAcceleration(libra::Vector<3> s, libra::Vector<3> sr, double GM); - - std::set third_body_list_; //!< List of celestial bodies to calculate the third body disturbances - libra::Vector<3> thirdbody_acc_i_{0}; //!< Calculated third body disturbance acceleration in the inertial frame [m/s2] + libra::Vector<3> CalcAcceleration(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2); }; #endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ From 762dc7ff426def3f939d5d147df05d5200dbe2a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:20:04 +0100 Subject: [PATCH 0451/1086] Rename --- .../solar_radiation_pressure_disturbance.cpp | 4 ++-- .../solar_radiation_pressure_disturbance.hpp | 4 ++-- src/disturbances/surface_force.cpp | 12 ++++++------ src/disturbances/surface_force.hpp | 12 ++++++------ 4 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 0da745c51..34650598d 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -19,8 +19,8 @@ void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& d CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSrp().CalcTruePressure()); } -void SolarRadiation::CalcCoefficients(libra::Vector<3>& input_b, double item) { - UNUSED(input_b); +void SolarRadiation::CalcCoefficients(libra::Vector<3>& input_direction_b, double item) { + UNUSED(input_direction_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface double area = surfaces_[i].GetArea(); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 17b021364..e6f72eb30 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -49,10 +49,10 @@ class SolarRadiation : public SurfaceForce { /** * @fn CalcCoefficients * @brief Override CalcCoefficients function of SurfaceForce - * @param [in] input_b: Direction vector of the sun at the body frame + * @param [in] input_direction_b: Direction vector of the sun at the body frame * @param [in] item: Solar pressure [N/m^2] */ - void CalcCoefficients(libra::Vector<3>& input_b, double item); + void CalcCoefficients(libra::Vector<3>& input_direction_b, double item); }; #endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index b4c4ce4c0..d0b3d651a 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -17,13 +17,13 @@ SurfaceForce::SurfaceForce(const vector& surfaces, const libra::Vector< sin_theta_.assign(num, 0.0); } -libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_b, double item) { - CalcTheta(input_b); - CalcCoefficients(input_b, item); +libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction_b, double item) { + CalcTheta(input_direction_b); + CalcCoefficients(input_direction_b, item); libra::Vector<3> force_b_N(0.0); libra::Vector<3> torque_b_Nm(0.0); - libra::Vector<3> input_b_normal(input_b); + libra::Vector<3> input_b_normal(input_direction_b); normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { @@ -45,8 +45,8 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_b, double return torque_b_Nm_; } -void SurfaceForce::CalcTheta(libra::Vector<3>& input_b) { - libra::Vector<3> input_b_normal(input_b); +void SurfaceForce::CalcTheta(libra::Vector<3>& input_direction_b) { + libra::Vector<3> input_b_normal(input_direction_b); normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 243b3fba7..7be8d13b1 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -50,25 +50,25 @@ class SurfaceForce : public SimpleDisturbance { /** * @fn CalcTorqueForce * @brief Calculate the torque and force - * @param [in] input_b: Direction of disturbance source at the body frame + * @param [in] input_direction_b: Direction of disturbance source at the body frame * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) * @return Calculated disturbance torque in body frame [Nm] */ - libra::Vector<3> CalcTorqueForce(libra::Vector<3>& input_b, double item); + libra::Vector<3> CalcTorqueForce(libra::Vector<3>& input_direction_b, double item); /** * @fn CalcTheta * @brief Calculate cosX and sinX - * @param [in] input_b: Direction of disturbance source at the body frame + * @param [in] input_direction_b: Direction of disturbance source at the body frame */ - void CalcTheta(libra::Vector<3>& input_b); + void CalcTheta(libra::Vector<3>& input_direction_b); /** * @fn CalcCoefficients * @brief Pure virtual function to define the calculation of the disturbance coefficients - * @param [in] input_b: Direction of disturbance source at the body frame + * @param [in] input_direction_b: Direction of disturbance source at the body frame * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) */ - virtual void CalcCoefficients(libra::Vector<3>& input_b, double item) = 0; + virtual void CalcCoefficients(libra::Vector<3>& input_direction_b, double item) = 0; }; #endif // S2E_DISTURBANCES_SURFACE_FORCE_HPP_ From aef9b3f3b024710d5d738d95ba83202420d80b75 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:23:58 +0100 Subject: [PATCH 0452/1086] Fix comments --- src/disturbances/air_drag.hpp | 2 ++ src/disturbances/geopotential.hpp | 4 ++++ src/disturbances/gravity_gradient.hpp | 2 ++ src/disturbances/magnetic_disturbance.hpp | 2 ++ src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 ++ src/disturbances/third_body_gravity.hpp | 2 ++ 6 files changed, 14 insertions(+) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index f9fe80b6f..7c4f471f3 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -35,6 +35,8 @@ class AirDrag : public SurfaceForce { /** * @fn Update * @brief Override Updates function of SimpleDisturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index cbd52814f..b25b7ec93 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -23,6 +23,8 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn GeoPotential * @brief Constructor + * @param [in] degree: Maximum degree setting to calculate the geo-potential + * @param [in] file_path: EGM96 coefficients file path * @param [in] is_calculation_enabled: Calculation flag */ GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled = true); @@ -30,6 +32,8 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn Update * @brief Override Updates function of SimpleDisturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment &local_environment, const Dynamics &dynamics); diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 044c0d679..2d5cd8637 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -36,6 +36,8 @@ class GravityGradient : public SimpleDisturbance { /** * @fn Update * @brief Override Updates function of SimpleDisturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 261c9a7bd..28d7e7374 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -28,6 +28,8 @@ class MagDisturbance : public SimpleDisturbance { /** * @fn Update * @brief Override Updates function of SimpleDisturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index e6f72eb30..0e83c6f4e 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -30,6 +30,8 @@ class SolarRadiation : public SurfaceForce { /** * @fn Update * @brief Override Updates function of SimpleDisturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 4d070d478..6179a2b88 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -35,6 +35,8 @@ class ThirdBodyGravity : public AccelerationDisturbance { /** * @fn Update * @brief Update third body disturbance + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); From d158a19e2460b763d7eda86f022f20cad58c0bab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:35:33 +0100 Subject: [PATCH 0453/1086] Remove unnecessary private variables --- src/disturbances/air_drag.cpp | 11 +++++------ src/disturbances/air_drag.hpp | 3 +-- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 706a7be79..f86997d8f 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -23,17 +23,16 @@ AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center } void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - double air_dens = local_environment.GetAtmosphere().GetAirDensity(); - Vector<3> tmp = dynamics.GetOrbit().GetSatVelocity_b(); - CalcTorqueForce(tmp, air_dens); + double air_density_kg_m3 = local_environment.GetAtmosphere().GetAirDensity(); + Vector<3> velocity_b_m_s = dynamics.GetOrbit().GetSatVelocity_b(); + CalcTorqueForce(velocity_b_m_s, air_density_kg_m3); } -void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens) { +void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_density_kg_m3) { double velocity_norm_m_s = norm(velocity_b_m_s); - rho_kg_m3_ = air_dens; CalCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { - double k = 0.5 * rho_kg_m3_ * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); + double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); normal_coefficients_[i] = k * cn_[i]; tangential_coefficients_[i] = k * ct_[i]; } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 7c4f471f3..c710da54a 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -55,7 +55,6 @@ class AirDrag : public SurfaceForce { private: vector cn_; //!< Coefficients for out-plane force vector ct_; //!< Coefficients for in-plane force - double rho_kg_m3_; //!< Air density [kg/m^3] double wall_temperature_K_; //!< Temperature of surface [K] double molecular_temperature_K_; //!< Temperature of atmosphere [K] double molecular_weight_g_mol_; //!< Molecular weight [g/mol] @@ -66,7 +65,7 @@ class AirDrag : public SurfaceForce { * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ - void CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens); + void CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_density_kg_m3); // internal function for calculation /** From 688d4577fd662b1d4ada6aad1a605e0023011c7f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:38:00 +0100 Subject: [PATCH 0454/1086] Add const --- src/disturbances/air_drag.cpp | 8 ++++---- src/disturbances/air_drag.hpp | 8 ++++---- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/surface_force.hpp | 2 +- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index f86997d8f..465a0d9ed 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -28,7 +28,7 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& CalcTorqueForce(velocity_b_m_s, air_density_kg_m3); } -void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_density_kg_m3) { +void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3) { double velocity_norm_m_s = norm(velocity_b_m_s); CalCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { @@ -38,21 +38,21 @@ void AirDrag::CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_dens } } -double AirDrag::CalcFuncPi(double s) { +double AirDrag::CalcFuncPi(const double s) { double x; double erfs = erf(s); // ERF function is defined in math standard library x = s * exp(-s * s) + sqrt(libra::pi) * (s * s + 0.5) * (1.0 + erfs); return x; } -double AirDrag::CalcFuncChi(double s) { +double AirDrag::CalcFuncChi(const double s) { double x; double erfs = erf(s); x = exp(-s * s) + sqrt(libra::pi) * s * (1.0 + erfs); return x; } -void AirDrag::CalCnCt(Vector<3>& velocity_b_m_s) { +void AirDrag::CalCnCt(const Vector<3>& velocity_b_m_s) { double velocity_norm_m_s = norm(velocity_b_m_s); // Re-emitting speed diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index c710da54a..59442b19b 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -65,7 +65,7 @@ class AirDrag : public SurfaceForce { * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] * @param [in] air_dens: Air density around the spacecraft [kg/m^3] */ - void CalcCoefficients(libra::Vector<3>& velocity_b_m_s, double air_density_kg_m3); + void CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3); // internal function for calculation /** @@ -73,17 +73,17 @@ class AirDrag : public SurfaceForce { * @brief Calculate the Cn and Ct * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] */ - void CalCnCt(libra::Vector<3>& velocity_b_m_s); + void CalCnCt(const libra::Vector<3>& velocity_b_m_s); /** * @fn CalcFuncPi * @brief Calculate The Pi function in the algorithm */ - double CalcFuncPi(double s); + double CalcFuncPi(const double s); /** * @fn CalcFuncChi * @brief Calculate The Chi function in the algorithm */ - double CalcFuncChi(double s); + double CalcFuncChi(const double s); }; #endif // S2E_DISTURBANCES_AIR_DRAG_HPP_ diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 34650598d..8555f4965 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -19,7 +19,7 @@ void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& d CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSrp().CalcTruePressure()); } -void SolarRadiation::CalcCoefficients(libra::Vector<3>& input_direction_b, double item) { +void SolarRadiation::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { UNUSED(input_direction_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 0e83c6f4e..5888accd0 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -54,7 +54,7 @@ class SolarRadiation : public SurfaceForce { * @param [in] input_direction_b: Direction vector of the sun at the body frame * @param [in] item: Solar pressure [N/m^2] */ - void CalcCoefficients(libra::Vector<3>& input_direction_b, double item); + void CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item); }; #endif // S2E_DISTURBANCES_SOLAR_RADIATION_PRESSURE_DISTURBANCE_HPP_ diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 7be8d13b1..8d5885992 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -68,7 +68,7 @@ class SurfaceForce : public SimpleDisturbance { * @param [in] input_direction_b: Direction of disturbance source at the body frame * @param [in] item: Parameter which decide the magnitude of the disturbances (e.g., Solar flux, air density) */ - virtual void CalcCoefficients(libra::Vector<3>& input_direction_b, double item) = 0; + virtual void CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) = 0; }; #endif // S2E_DISTURBANCES_SURFACE_FORCE_HPP_ From 456a57f48c296043b5ed8f6789a7bedf569b0609 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:42:42 +0100 Subject: [PATCH 0455/1086] Fix function name --- src/disturbances/geopotential.cpp | 8 ++++---- src/disturbances/geopotential.hpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 63afade9d..efaa798d7 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -36,14 +36,14 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const // In S2E, 0 degree term is inside the SimpleCircularOrbit calculation c_[0][0] = 0.0; if (degree_ >= 2) { - if (!ReadCoefficientsEGM96(file_path)) { + if (!ReadCoefficientsEgm96(file_path)) { degree_ = 0; std::cout << "degree of GeoPotential set as " << degree_ << "\n"; } } } -bool GeoPotential::ReadCoefficientsEGM96(std::string file_name) { +bool GeoPotential::ReadCoefficientsEgm96(std::string file_name) { std::ifstream coeff_file(file_name); if (!coeff_file.is_open()) { std::cerr << "file open error:Geopotential\n"; @@ -72,7 +72,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); #endif - CalcAccelerationECEF(dynamics.GetOrbit().GetSatPosition_ecef()); + CalcAccelerationEcef(dynamics.GetOrbit().GetSatPosition_ecef()); #ifdef DEBUG_GEOPOTENTIAL end = chrono::system_clock::now(); time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); @@ -83,7 +83,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } -void GeoPotential::CalcAccelerationECEF(const Vector<3> &position_ecef_m) { +void GeoPotential::CalcAccelerationEcef(const Vector<3> &position_ecef_m) { ecef_x_m_ = position_ecef_m[0], ecef_y_m_ = position_ecef_m[1], ecef_z_m_ = position_ecef_m[2]; radius_m_ = sqrt(ecef_x_m_ * ecef_x_m_ + ecef_y_m_ * ecef_y_m_ + ecef_z_m_ * ecef_z_m_); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index b25b7ec93..5e60a5e36 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -65,18 +65,18 @@ class GeoPotential : public AccelerationDisturbance { double time_ms_ = 0.0; //!< Calculation time [ms] /** - * @fn CalcAccelerationECEF + * @fn CalcAccelerationEcef * @brief Calculate the high-order earth gravity in the ECEF frame * @param [in] position_ecef_m: Position of the spacecraft in the ECEF fram [m] */ - void CalcAccelerationECEF(const Vector<3> &position_ecef_m); + void CalcAccelerationEcef(const Vector<3> &position_ecef_m); /** - * @fn ReadCoefficientsEGM96 + * @fn ReadCoefficientsEgm96 * @brief Read the geo-potential coefficients for the EGM96 model * @param [in] file_name: Coefficient file name */ - bool ReadCoefficientsEGM96(std::string file_name); + bool ReadCoefficientsEgm96(std::string file_name); /** * @fn v_w_nn_update From 26eb3da0292edf0ca254e654e9f92ebb41bf4767 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 15:59:53 +0100 Subject: [PATCH 0456/1086] fix n and m --- src/disturbances/geopotential.cpp | 70 +++++++++++++++---------------- src/disturbances/geopotential.hpp | 2 +- 2 files changed, 36 insertions(+), 36 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index efaa798d7..be8820de8 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -52,15 +52,15 @@ bool GeoPotential::ReadCoefficientsEgm96(std::string file_name) { int num_coeff = ((degree_ + 1) * (degree_ + 2) / 2) - 3; //-3 for C00,C10,C11 for (int i = 0; i < num_coeff; i++) { - int n_, m_; + int n, m; double c_nm_norm, s_nm_norm; std::string line; getline(coeff_file, line); std::istringstream streamline(line); - streamline >> n_ >> m_ >> c_nm_norm >> s_nm_norm; + streamline >> n >> m >> c_nm_norm >> s_nm_norm; - c_[n_][m_] = c_nm_norm; - s_[n_][m_] = s_nm_norm; + c_[n][m] = c_nm_norm; + s_[n][m] = s_nm_norm; } return true; } @@ -94,49 +94,49 @@ void GeoPotential::CalcAccelerationEcef(const Vector<3> &position_ecef_m) { // n=m=0 v[0][0] = environment::earth_equatorial_radius_m / radius_m_; w[0][0] = 0.0; - m = 0; + m_ = 0; - while (m < degree_vw) { - for (n = m + 1; n <= degree_vw; n++) { - if (n <= m + 1) - v_w_nm_update(&v[n][m], &w[n][m], v[n - 1][m], w[n - 1][m], 0.0, 0.0); + while (m_ < degree_vw) { + for (n_ = m_ + 1; n_ <= degree_vw; n_++) { + if (n_ <= m_ + 1) + v_w_nm_update(&v[n_][m_], &w[n_][m_], v[n_ - 1][m_], w[n_ - 1][m_], 0.0, 0.0); else - v_w_nm_update(&v[n][m], &w[n][m], v[n - 1][m], w[n - 1][m], v[n - 2][m], w[n - 2][m]); + v_w_nm_update(&v[n_][m_], &w[n_][m_], v[n_ - 1][m_], w[n_ - 1][m_], v[n_ - 2][m_], w[n_ - 2][m_]); } // next step - m++; - n = m; - v_w_nn_update(&v[n][m], &w[n][m], v[n - 1][m - 1], w[n - 1][m - 1]); + m_++; + n_ = m_; + v_w_nn_update(&v[n_][m_], &w[n_][m_], v[n_ - 1][m_ - 1], w[n_ - 1][m_ - 1]); } // Calc Acceleration acceleration_ecef_m_s2_ *= 0.0; - for (n = 0; n <= degree_; n++) // this loop can integrate with previous loop + for (n_ = 0; n_ <= degree_; n_++) // this loop can integrate with previous loop { - m = 0; - double n_d = (double)n; + m_ = 0; + double n_d = (double)n_; double normalize = sqrt((2.0 * n_d + 1.0) / (2.0 * n_d + 3.0)); double normalize_xy = normalize * sqrt((n_d + 2.0) * (n_d + 1.0) / 2.0); - // m==0 - acceleration_ecef_m_s2_[0] += -c_[n][0] * v[n + 1][1] * normalize_xy; - acceleration_ecef_m_s2_[1] += -c_[n][0] * w[n + 1][1] * normalize_xy; - acceleration_ecef_m_s2_[2] += (n + 1.0) * (-c_[n][0] * v[n + 1][0] - s_[n][0] * w[n + 1][0]) * normalize; - for (m = 1; m <= n; m++) { - double m_d = (double)m; + // m_==0 + acceleration_ecef_m_s2_[0] += -c_[n_][0] * v[n_ + 1][1] * normalize_xy; + acceleration_ecef_m_s2_[1] += -c_[n_][0] * w[n_ + 1][1] * normalize_xy; + acceleration_ecef_m_s2_[2] += (n_ + 1.0) * (-c_[n_][0] * v[n_ + 1][0] - s_[n_][0] * w[n_ + 1][0]) * normalize; + for (m_ = 1; m_ <= n_; m_++) { + double m_d = (double)m_; double factorial = (n_d - m_d + 1.0) * (n_d - m_d + 2.0); double normalize_xy1 = normalize * sqrt((n_d + m_d + 1.0) * (n_d + m_d + 2.0)); double normalize_xy2; - if (m == 1) + if (m_ == 1) normalize_xy2 = normalize * sqrt(factorial) * sqrt(2.0); else normalize_xy2 = normalize * sqrt(factorial); double normalize_z = normalize * sqrt((n_d + m_d + 1.0) / (n_d - m_d + 1.0)); - acceleration_ecef_m_s2_[0] += 0.5 * (normalize_xy1 * (-c_[n][m] * v[n + 1][m + 1] - s_[n][m] * w[n + 1][m + 1]) + - normalize_xy2 * (c_[n][m] * v[n + 1][m - 1] + s_[n][m] * w[n + 1][m - 1])); - acceleration_ecef_m_s2_[1] += 0.5 * (normalize_xy1 * (-c_[n][m] * w[n + 1][m + 1] + s_[n][m] * v[n + 1][m + 1]) + - normalize_xy2 * (-c_[n][m] * w[n + 1][m - 1] + s_[n][m] * v[n + 1][m - 1])); - acceleration_ecef_m_s2_[2] += (n_d - m_d + 1.0) * (-c_[n][m] * v[n + 1][m] - s_[n][m] * w[n + 1][m]) * normalize_z; + acceleration_ecef_m_s2_[0] += 0.5 * (normalize_xy1 * (-c_[n_][m_] * v[n_ + 1][m_ + 1] - s_[n_][m_] * w[n_ + 1][m_ + 1]) + + normalize_xy2 * (c_[n_][m_] * v[n_ + 1][m_ - 1] + s_[n_][m_] * w[n_ + 1][m_ - 1])); + acceleration_ecef_m_s2_[1] += 0.5 * (normalize_xy1 * (-c_[n_][m_] * w[n_ + 1][m_ + 1] + s_[n_][m_] * v[n_ + 1][m_ + 1]) + + normalize_xy2 * (-c_[n_][m_] * w[n_ + 1][m_ - 1] + s_[n_][m_] * v[n_ + 1][m_ - 1])); + acceleration_ecef_m_s2_[2] += (n_d - m_d + 1.0) * (-c_[n_][m_] * v[n_ + 1][m_] - s_[n_][m_] * w[n_ + 1][m_]) * normalize_z; } } acceleration_ecef_m_s2_ *= @@ -146,15 +146,15 @@ void GeoPotential::CalcAccelerationEcef(const Vector<3> &position_ecef_m) { } void GeoPotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev, const double w_prev) { - if (n != m) return; + if (n_ != m_) return; - double n_d = (double)n; + double n_d = (double)n_; double tmp = environment::earth_equatorial_radius_m / (radius_m_ * radius_m_); double x_tmp = ecef_x_m_ * tmp; double y_tmp = ecef_y_m_ * tmp; double c_normalize; - if (n == 1) + if (n_ == 1) c_normalize = (2.0 * n_d - 1.0) * sqrt(2.0 * n_d + 1.0); else c_normalize = sqrt((2.0 * n_d + 1.0) / (2.0 * n_d)); @@ -165,10 +165,10 @@ void GeoPotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev } void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2) { - if (n == m) return; + if (n_ == m_) return; - double m_d = (double)m; - double n_d = (double)n; + double m_d = (double)m_; + double n_d = (double)n_; double tmp = environment::earth_equatorial_radius_m / (radius_m_ * radius_m_); double z_tmp = ecef_z_m_ * tmp; @@ -178,7 +178,7 @@ void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev double c_normalize, c2_normalize; c_normalize = sqrt(((2.0 * n_d + 1.0) * (n_d - m_d)) / ((2.0 * n_d - 1.0) * (n_d + m_d))); - if (n <= 1) + if (n_ <= 1) c2_normalize = 1.0; else c2_normalize = sqrt(((2.0 * n_d - 1.0) * (n_d - m_d - 1.0)) / ((2.0 * n_d - 3.0) * (n_d + m_d - 1.0))); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 5e60a5e36..34134165c 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -51,7 +51,7 @@ class GeoPotential : public AccelerationDisturbance { private: int degree_; //!< Maximum degree setting to calculate the geo-potential - int n = 0, m = 0; //!< Degree and order (FIXME: follow naming rule) + int n_ = 0, m_ = 0; //!< Degree and order (FIXME: follow naming rule) vector> c_; //!< Cosine coefficients vector> s_; //!< Sine coefficients Vector<3> acceleration_ecef_m_s2_; //!< Calculated acceleration in the ECEF frame [m/s2] From 7cf42c90ca41dd91b30f17be7d506811e03968d7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:03:19 +0100 Subject: [PATCH 0457/1086] fix small --- src/disturbances/geopotential.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index be8820de8..0f55ca522 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -84,7 +84,9 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam } void GeoPotential::CalcAccelerationEcef(const Vector<3> &position_ecef_m) { - ecef_x_m_ = position_ecef_m[0], ecef_y_m_ = position_ecef_m[1], ecef_z_m_ = position_ecef_m[2]; + ecef_x_m_ = position_ecef_m[0]; + ecef_y_m_ = position_ecef_m[1]; + ecef_z_m_ = position_ecef_m[2]; radius_m_ = sqrt(ecef_x_m_ * ecef_x_m_ + ecef_y_m_ * ecef_y_m_ + ecef_z_m_ * ecef_z_m_); // Calc V and W From 28b5c09447e80ee84db8f892c8fac4f50f478375 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:06:37 +0100 Subject: [PATCH 0458/1086] Fix argument name --- src/disturbances/geopotential.hpp | 2 ++ src/disturbances/gravity_gradient.cpp | 8 ++++---- src/disturbances/gravity_gradient.hpp | 6 +++--- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index 34134165c..57a278b99 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -81,12 +81,14 @@ class GeoPotential : public AccelerationDisturbance { /** * @fn v_w_nn_update * @brief Calculate V and W function for n = m + * @note FIXME: fix function name */ void v_w_nn_update(double *v_nn, double *w_nn, const double v_prev, const double w_prev); /** * @fn v_w_nm_update * @brief Calculate V and W function for n not equal m + * @note FIXME: fix function name */ void v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2); }; diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 98070ac03..2fc1a5d7e 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -21,13 +21,13 @@ void GravityGradient::Update(const LocalEnvironment& local_environment, const Dy CalcTorque(local_environment.GetCelesInfo().GetCenterBodyPosFromSC_b(), dynamics.GetAttitude().GetInertiaTensor()); } -libra::Vector<3> GravityGradient::CalcTorque(const libra::Vector<3> r_b_m, const libra::Matrix<3, 3> I_b_kgm2) { - double r_norm_m = norm(r_b_m); - libra::Vector<3> u_b = r_b_m; // TODO: make undestructive normalize function for Vector +libra::Vector<3> GravityGradient::CalcTorque(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { + double r_norm_m = norm(earth_position_from_sc_b_m); + libra::Vector<3> u_b = earth_position_from_sc_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; double coeff = 3.0 * mu_m3_s2_ / pow(r_norm_m, 3.0); - torque_b_Nm_ = coeff * outer_product(u_b, I_b_kgm2 * u_b); + torque_b_Nm_ = coeff * outer_product(u_b, inertia_tensor_b_kgm2 * u_b); return torque_b_Nm_; } diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 2d5cd8637..be092c5cb 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -59,11 +59,11 @@ class GravityGradient : public SimpleDisturbance { /** * @fn CalcTorque * @brief Calculate gravity gradient torque - * @param [in] r_b_m: Position vector of the earth at body frame [m] - * @param [in] I_b_kgm2: Inertia Tensor at body frame [kg*m^2] + * @param [in] earth_position_from_sc_b_m: Position vector of the earth from spacecraft at body frame [m] + * @param [in] inertia_tensor_b_kgm2: Inertia Tensor at body frame [kg*m^2] * @return Calculated torque at body frame [Nm] */ - libra::Vector<3> CalcTorque(const libra::Vector<3> r_b_m, const libra::Matrix<3, 3> I_b_kgm2); + libra::Vector<3> CalcTorque(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2); }; #endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ From b6ea87c7e108d596b174cc2c3e767f64babd06b5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:21:06 +0100 Subject: [PATCH 0459/1086] Fix initialize files --- src/disturbances/disturbances.cpp | 6 +- src/disturbances/initialize_disturbances.cpp | 110 +++++++++---------- src/disturbances/initialize_disturbances.hpp | 37 ++++--- 3 files changed, 77 insertions(+), 76 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index a30b88f43..a764d534c 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -70,8 +70,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const new GravityGradient(InitGravityGradient(initialize_file_name_, global_environment->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); disturbances_list_.push_back(gg_dist); - SolarRadiation* srp_dist = - new SolarRadiation(InitSRDist(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); + SolarRadiation* srp_dist = new SolarRadiation( + InitSolarRadiationPressureDisturbance(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(srp_dist); ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->ini_base_fname_)); @@ -82,7 +82,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const AirDrag* air_dist = new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(air_dist); - MagDisturbance* mag_dist = new MagDisturbance(InitMagDisturbance(initialize_file_name_, structure->GetRMMParams())); + MagDisturbance* mag_dist = new MagDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetRMMParams())); disturbances_list_.push_back(mag_dist); GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 177428824..00b9b8dfc 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -9,110 +9,110 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -#define MIN_VAL 1e-9 -AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b) { - auto conf = IniAccess(ini_path); +AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector& surfaces, const Vector<3>& center_of_gravity_b_m) { + auto conf = IniAccess(initialize_file_path); const char* section = "AIR_DRAG"; - double t_w = conf.ReadDouble(section, "wall_temperature_degC") + 273.0; - double t_m = conf.ReadDouble(section, "molecular_temperature_degC") + 273.0; - double molecular = conf.ReadDouble(section, "molecular_weight"); + const double wall_temperature_K = conf.ReadDouble(section, "wall_temperature_degC") + 273.0; + const double molecular_temperature_K = conf.ReadDouble(section, "molecular_temperature_degC") + 273.0; + const double molecular_weight_g_mol = conf.ReadDouble(section, "molecular_weight"); - bool calcen = conf.ReadEnable(section, CALC_LABEL); - bool logen = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + const bool is_log_enable = conf.ReadEnable(section, LOG_LABEL); - AirDrag airdrag(surfaces, cg_b, t_w, t_m, molecular, calcen); - airdrag.IsLogEnabled = logen; + AirDrag air_drag(surfaces, center_of_gravity_b_m, wall_temperature_K, molecular_temperature_K, molecular_weight_g_mol, is_calc_enable); + air_drag.IsLogEnabled = is_log_enable; - return airdrag; + return air_drag; } -SolarRadiation InitSRDist(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b) { - auto conf = IniAccess(ini_path); +SolarRadiation InitSolarRadiationPressureDisturbance(const std::string initialize_file_path, const std::vector& surfaces, + const Vector<3>& center_of_gravity_b_m) { + auto conf = IniAccess(initialize_file_path); const char* section = "SOLAR_RADIATION_PRESSURE_DISTURBANCE"; - bool calcen = conf.ReadEnable(section, CALC_LABEL); - bool logen = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + const bool is_log_enable = conf.ReadEnable(section, LOG_LABEL); - SolarRadiation srdist(surfaces, cg_b, calcen); - srdist.IsLogEnabled = logen; + SolarRadiation srp_disturbance(surfaces, center_of_gravity_b_m, is_calc_enable); + srp_disturbance.IsLogEnabled = is_log_enable; - return srdist; + return srp_disturbance; } -GravityGradient InitGravityGradient(std::string ini_path) { - auto conf = IniAccess(ini_path); +GravityGradient InitGravityGradient(const std::string initialize_file_path) { + auto conf = IniAccess(initialize_file_path); const char* section = "GRAVITY_GRADIENT"; - bool calcen = conf.ReadEnable(section, CALC_LABEL); - GravityGradient ggdist(calcen); - ggdist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + GravityGradient gg_disturbance(is_calc_enable); + gg_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); - return ggdist; + return gg_disturbance; } -GravityGradient InitGravityGradient(std::string ini_path, const double mu_m3_s2) { - auto conf = IniAccess(ini_path); +GravityGradient InitGravityGradient(const std::string initialize_file_path, const double mu_m3_s2) { + auto conf = IniAccess(initialize_file_path); const char* section = "GRAVITY_GRADIENT"; - bool calcen = conf.ReadEnable(section, CALC_LABEL); - GravityGradient ggdist(mu_m3_s2, calcen); - ggdist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + GravityGradient gg_disturbance(mu_m3_s2, is_calc_enable); + gg_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); - return ggdist; + return gg_disturbance; } -MagDisturbance InitMagDisturbance(std::string ini_path, const RMMParams& rmm_params) { - auto conf = IniAccess(ini_path); +MagDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params) { + auto conf = IniAccess(initialize_file_path); const char* section = "MAGNETIC_DISTURBANCE"; - bool calcen = conf.ReadEnable(section, CALC_LABEL); - MagDisturbance mag_dist(rmm_params, calcen); - mag_dist.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + MagDisturbance mag_disturbance(rmm_params, is_calc_enable); + mag_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); - return mag_dist; + return mag_disturbance; } -GeoPotential InitGeoPotential(std::string ini_path) { - auto conf = IniAccess(ini_path); +GeoPotential InitGeoPotential(const std::string initialize_file_path) { + auto conf = IniAccess(initialize_file_path); const char* section = "GEOPOTENTIAL"; - int degree = conf.ReadInt(section, "degree"); - std::string file_path = conf.ReadString(section, "coefficients_file_path"); - bool calcen = conf.ReadEnable(section, CALC_LABEL); + const int degree = conf.ReadInt(section, "degree"); + const std::string coefficients_file_path = conf.ReadString(section, "coefficients_file_path"); - GeoPotential geop(degree, file_path, calcen); - geop.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + GeoPotential geopotential_disturbance(degree, coefficients_file_path, is_calc_enable); + geopotential_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); - return geop; + return geopotential_disturbance; } -ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes) { +ThirdBodyGravity InitThirdBodyGravity(const std::string initialize_file_path, const std::string ini_path_celes) { // Generate a list of bodies to be calculated in "CelesInfo" auto conf_celes = IniAccess(ini_path_celes); const char* section_celes = "CELESTIAL_INFORMATION"; const int num_of_selected_body = conf_celes.ReadInt(section_celes, "number_of_selected_body"); - std::string center_object = conf_celes.ReadString(section_celes, "center_object"); - std::set selected_body_list; + const std::string center_object = conf_celes.ReadString(section_celes, "center_object"); + std::set selected_body_list; for (int i = 0; i < num_of_selected_body; i++) { std::string selected_body_id = "selected_body_name(" + std::to_string(i) + ")"; selected_body_list.insert(conf_celes.ReadString(section_celes, selected_body_id.c_str())); } // Generate a list of bodies to be calculated in "ThirdBodyGravity" from the list of bodies of "CelesInfo" - auto conf = IniAccess(ini_path); + auto conf = IniAccess(initialize_file_path); const char* section = "THIRD_BODY_GRAVITY"; const int num_of_third_body = conf.ReadInt(section, "number_of_third_body"); - std::set third_body_list; + std::set third_body_list; // Generate the list of the third object if "calculation=ENABLE" if (conf.ReadEnable(section, CALC_LABEL)) { for (int i = 0; i < num_of_third_body; i++) { - std::string third_body_id = "third_body_name(" + std::to_string(i) + ")"; - std::string third_body_name = conf.ReadString(section, third_body_id.c_str()); + const std::string third_body_id = "third_body_name(" + std::to_string(i) + ")"; + const std::string third_body_name = conf.ReadString(section, third_body_id.c_str()); // If the object specified by `third_body` in "SampleDisturbance.ini" is // the center object of the orbital propagation, the system prints an // error message. @@ -125,9 +125,9 @@ ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path } } - bool calcen = conf.ReadEnable(section, CALC_LABEL); - ThirdBodyGravity thirdbodyg(third_body_list, calcen); - thirdbodyg.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); + ThirdBodyGravity third_body_disturbance(third_body_list, is_calc_enable); + third_body_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); - return thirdbodyg; + return third_body_disturbance; } diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index 7bb8481fb..eda8aa992 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -16,53 +16,54 @@ /** * @fn InitAirDrag * @brief Initialize AirDrag class - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path * @param [in] surfaces: surface information of the spacecraft - * @param [in] cg_b: Center of gravity position vector at body frame [m] + * @param [in] center_of_gravity_b_m: Center of gravity position vector at body frame [m] */ -AirDrag InitAirDrag(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b); +AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector& surfaces, const Vector<3>& center_of_gravity_b_m); /** - * @fn InitSRDist + * @fn InitSolarRadiationPressureDisturbance * @brief Initialize SolarRadiation class - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path * @param [in] surfaces: surface information of the spacecraft - * @param [in] cg_b: Center of gravity position vector at body frame [m] + * @param [in] center_of_gravity_b_m: Center of gravity position vector at body frame [m] */ -SolarRadiation InitSRDist(std::string ini_path, const std::vector& surfaces, const Vector<3>& cg_b); +SolarRadiation InitSolarRadiationPressureDisturbance(const std::string initialize_file_path, const std::vector& surfaces, + const Vector<3>& center_of_gravity_b_m); /** * @fn InitGravityGradient * @brief Initialize GravityGradient class with earth gravitational constant - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path */ -GravityGradient InitGravityGradient(std::string ini_path); +GravityGradient InitGravityGradient(const std::string initialize_file_path); /** * @fn InitGravityGradient * @brief Initialize GravityGradient class with earth gravitational constant - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path * @param [in] mu_m3_s2: Gravitational constant [m3/s2] */ -GravityGradient InitGravityGradient(std::string ini_path, const double mu_m3_s2); +GravityGradient InitGravityGradient(const std::string initialize_file_path, const double mu_m3_s2); /** - * @fn InitMagDisturbance + * @fn InitMagneticDisturbance * @brief Initialize MagDisturbance class with earth gravitational constant - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path * @param [in] rmm_params: RMM parameters */ -MagDisturbance InitMagDisturbance(std::string ini_path, const RMMParams& rmm_params); +MagDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params); /** * @fn InitGeoPotential * @brief Initialize GeoPotential class with earth gravitational constant - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path */ -GeoPotential InitGeoPotential(std::string ini_path); +GeoPotential InitGeoPotential(const std::string initialize_file_path); /** * @fn InitThirdBodyGravity * @brief Initialize ThirdBodyGravity class with earth gravitational constant - * @param [in] ini_path: Initialize file path + * @param [in] initialize_file_path: Initialize file path * @param [in] ini_path_celes: Initialize file path for the celestial information */ -ThirdBodyGravity InitThirdBodyGravity(std::string ini_path, std::string ini_path_celes); +ThirdBodyGravity InitThirdBodyGravity(const std::string initialize_file_path, const std::string ini_path_celes); #endif // S2E_DISTURBANCES_INITIALIZE_DISTURBANCES_HPP_ From e069e16f9ce1807ea83840e871509c80f1674683 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:24:07 +0100 Subject: [PATCH 0460/1086] Add unit into function name --- src/disturbances/gravity_gradient.cpp | 5 +++-- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 4 ++-- src/disturbances/magnetic_disturbance.hpp | 5 +++-- src/disturbances/third_body_gravity.cpp | 4 ++-- src/disturbances/third_body_gravity.hpp | 2 +- 6 files changed, 12 insertions(+), 10 deletions(-) diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 2fc1a5d7e..113998cda 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -18,10 +18,11 @@ GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculatio void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor - CalcTorque(local_environment.GetCelesInfo().GetCenterBodyPosFromSC_b(), dynamics.GetAttitude().GetInertiaTensor()); + CalcTorque_b_Nm(local_environment.GetCelesInfo().GetCenterBodyPosFromSC_b(), dynamics.GetAttitude().GetInertiaTensor()); } -libra::Vector<3> GravityGradient::CalcTorque(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { +libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, + const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { double r_norm_m = norm(earth_position_from_sc_b_m); libra::Vector<3> u_b = earth_position_from_sc_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index be092c5cb..448a062ad 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -63,7 +63,7 @@ class GravityGradient : public SimpleDisturbance { * @param [in] inertia_tensor_b_kgm2: Inertia Tensor at body frame [kg*m^2] * @return Calculated torque at body frame [Nm] */ - libra::Vector<3> CalcTorque(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2); + libra::Vector<3> CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2); }; #endif // S2E_DISTURBANCES_GRAVITY_GRADIENT_HPP_ diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 2a36bf581..f6e65aaf4 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -17,7 +17,7 @@ MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calcul rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); } -Vector<3> MagDisturbance::CalcTorque(const Vector<3>& magnetic_field_b_nT) { +Vector<3> MagDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { CalcRMM(); torque_b_Nm_ = kMagUnit_ * outer_product(rmm_b_Am2_, magnetic_field_b_nT); return torque_b_Nm_; @@ -26,7 +26,7 @@ Vector<3> MagDisturbance::CalcTorque(const Vector<3>& magnetic_field_b_nT) { void MagDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - CalcTorque(local_environment.GetMag().GetMag_b()); + CalcTorque_b_Nm(local_environment.GetMag().GetMag_b()); } void MagDisturbance::CalcRMM() { diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 28d7e7374..86a52e31a 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -57,11 +57,12 @@ class MagDisturbance : public SimpleDisturbance { */ void CalcRMM(); /** - * @fn CalcTorque + * @fn CalcTorque_b_Nm * @brief Calculate magnetic disturbance torque * @param [in] magnetic_field_b_nT: Magnetic field vector at the body frame [nT] + * @return Calculated disturbance torque in body frame [Nm] */ - libra::Vector<3> CalcTorque(const libra::Vector<3>& magnetic_field_b_nT); + libra::Vector<3> CalcTorque_b_Nm(const libra::Vector<3>& magnetic_field_b_nT); }; #endif // S2E_DISTURBANCES_MAGNETIC_DISTURBANCE_HPP_ diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 0ed81d349..0ab9194c8 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -21,12 +21,12 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); - third_body_acceleration_i_m_s2_ = CalcAcceleration(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); + third_body_acceleration_i_m_s2_ = CalcAcceleration_b_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; } } -libra::Vector<3> ThirdBodyGravity::CalcAcceleration(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { +libra::Vector<3> ThirdBodyGravity::CalcAcceleration_b_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { libra::Vector<3> acceleration_i_m_s2; double s_norm = libra::norm(s); diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 6179a2b88..b3b483977 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -64,7 +64,7 @@ class ThirdBodyGravity : public AccelerationDisturbance { * @param [in] GM: The gravitational constants of the third celestial body [m3/s2] * @return Third body disturbance acceleration in the inertial frame in unit [m/s2] */ - libra::Vector<3> CalcAcceleration(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2); + libra::Vector<3> CalcAcceleration_b_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2); }; #endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ From 5e2a3f66e87f347664dc26707b321679fb7264b6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:32:07 +0100 Subject: [PATCH 0461/1086] Fix comments --- src/disturbances/air_drag.hpp | 4 +++- src/disturbances/initialize_disturbances.hpp | 4 ++++ src/disturbances/simple_disturbance.hpp | 4 ++++ src/disturbances/third_body_gravity.cpp | 4 ++-- src/disturbances/third_body_gravity.hpp | 5 +++-- 5 files changed, 16 insertions(+), 5 deletions(-) diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 59442b19b..f3578bca3 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -63,7 +63,7 @@ class AirDrag : public SurfaceForce { * @fn CalcCoefficients * @brief Override CalcCoefficients function of SurfaceForce * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] - * @param [in] air_dens: Air density around the spacecraft [kg/m^3] + * @param [in] air_density_kg_m3: Air density around the spacecraft [kg/m^3] */ void CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3); @@ -77,11 +77,13 @@ class AirDrag : public SurfaceForce { /** * @fn CalcFuncPi * @brief Calculate The Pi function in the algorithm + * @param [in] s: Independent variable of the Pi function */ double CalcFuncPi(const double s); /** * @fn CalcFuncChi * @brief Calculate The Chi function in the algorithm + * @param [in] s: Independent variable of the Chi function */ double CalcFuncChi(const double s); }; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index eda8aa992..0ecd38ea6 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -21,6 +21,7 @@ * @param [in] center_of_gravity_b_m: Center of gravity position vector at body frame [m] */ AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector& surfaces, const Vector<3>& center_of_gravity_b_m); + /** * @fn InitSolarRadiationPressureDisturbance * @brief Initialize SolarRadiation class @@ -37,6 +38,7 @@ SolarRadiation InitSolarRadiationPressureDisturbance(const std::string initializ * @param [in] initialize_file_path: Initialize file path */ GravityGradient InitGravityGradient(const std::string initialize_file_path); + /** * @fn InitGravityGradient * @brief Initialize GravityGradient class with earth gravitational constant @@ -52,12 +54,14 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons * @param [in] rmm_params: RMM parameters */ MagDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params); + /** * @fn InitGeoPotential * @brief Initialize GeoPotential class with earth gravitational constant * @param [in] initialize_file_path: Initialize file path */ GeoPotential InitGeoPotential(const std::string initialize_file_path); + /** * @fn InitThirdBodyGravity * @brief Initialize ThirdBodyGravity class with earth gravitational constant diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp index d03fb07bc..6d8e0ffa2 100644 --- a/src/disturbances/simple_disturbance.hpp +++ b/src/disturbances/simple_disturbance.hpp @@ -34,6 +34,8 @@ class SimpleDisturbance : public Disturbance, public ILoggable { /** * @fn UpdateIfEnabled * @brief Update calculated disturbance when the calculation flag is true + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { if (is_calculation_enabled_) { @@ -47,6 +49,8 @@ class SimpleDisturbance : public Disturbance, public ILoggable { /** * @fn Update * @brief Pure virtual function to define the disturbance calculation + * @param [in] local_environment: Local environment information + * @param [in] dynamics: Dynamics information */ virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; }; diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 0ab9194c8..49b0b9cff 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -21,12 +21,12 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); - third_body_acceleration_i_m_s2_ = CalcAcceleration_b_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); + third_body_acceleration_i_m_s2_ = CalcAcceleration_i_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; } } -libra::Vector<3> ThirdBodyGravity::CalcAcceleration_b_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { +libra::Vector<3> ThirdBodyGravity::CalcAcceleration_i_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { libra::Vector<3> acceleration_i_m_s2; double s_norm = libra::norm(s); diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index b3b483977..e8e0b2c1d 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -23,6 +23,7 @@ class ThirdBodyGravity : public AccelerationDisturbance { /** * @fn ThirdBodyGravity * @brief Constructor + * @param [in] third_body_list: List of calculation target bodies * @param [in] is_calculation_enabled: Calculation flag */ ThirdBodyGravity(const std::set third_body_list, const bool is_calculation_enabled = true); @@ -57,14 +58,14 @@ class ThirdBodyGravity : public AccelerationDisturbance { virtual std::string GetLogValue() const; /** - * @fn CalcAcceleration + * @fn CalcAcceleration_i_m_s2 * @brief Calculate and return the third body disturbance acceleration * @param [in] s: Position vector of the third celestial body from the origin in the inertial frame in unit [m] * @param [in] sr: Position vector of the third celestial body from the spacecraft in the inertial frame in unit [m] * @param [in] GM: The gravitational constants of the third celestial body [m3/s2] * @return Third body disturbance acceleration in the inertial frame in unit [m/s2] */ - libra::Vector<3> CalcAcceleration_b_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2); + libra::Vector<3> CalcAcceleration_i_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2); }; #endif // S2E_DISTURBANCES_THIRD_BODY_GRAVITY_HPP_ From 809fce03bc3151fb224764ac3a270440aa76c2e5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:40:40 +0100 Subject: [PATCH 0462/1086] fix small --- src/disturbances/geopotential.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 0f55ca522..fd9d48fd2 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -67,7 +67,7 @@ bool GeoPotential::ReadCoefficientsEgm96(std::string file_name) { void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynamics &dynamics) { #ifdef DEBUG_GEOPOTENTIAL - chrono::system_clock::time_ms_point start, end; + chrono::system_clock::time_point start, end; start = chrono::system_clock::now(); debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); #endif @@ -194,8 +194,8 @@ std::string GeoPotential::GetLogHeader() const { std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL - str_tmp += WriteVector("pos_", "ecef", "m", 3); - str_tmp += WriteScalar("time_ms_geop", "ms"); + str_tmp += WriteVector("geopotential_calculation_position_", "ecef", "m", 3); + str_tmp += WriteScalar("geopotential_calculation_time", "ms"); #endif str_tmp += WriteVector("geopotential_acceleration", "ecef", "m/s2", 3); From 72fea96fcff7ab14d5b5e0ff930908c760e428d2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:53:07 +0100 Subject: [PATCH 0463/1086] Revert initiali settings --- data/sample/initialize_files/sample_disturbance.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index d6e87a88b..2a46ae623 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -1,6 +1,6 @@ [GEOPOTENTIAL] // Enable only when the center object is defined as the Earth -calculation = ENABLE +calculation = DISABLE logging = ENABLE degree = 4 coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii @@ -34,7 +34,7 @@ logging = ENABLE [THIRD_BODY_GRAVITY] -calculation = ENABLE +calculation = DISABLE logging = ENABLE // The number of gravity-generating bodies other than the central body From 583c470f4fd888dc502cd60d5020f7e5d1f3942a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 15 Feb 2023 16:58:12 +0100 Subject: [PATCH 0464/1086] Add unit --- data/sample/initialize_files/sample_disturbance.ini | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index 2a46ae623..32da0bd19 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -20,7 +20,7 @@ logging = ENABLE // Condition of air drag wall_temperature_degC = 30 // Surface Temperature[degC] molecular_temperature_degC = 3 // Atmosphere Temperature[degC] -molecular_weight = 18.0 // Molecular weight of the thermosphere[g/mol] +molecular_weight_g_mol = 18.0 // Molecular weight of the thermosphere[g/mol] [SOLAR_RADIATION_PRESSURE_DISTURBANCE] diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 00b9b8dfc..0adfee485 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -16,7 +16,7 @@ AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector Date: Thu, 16 Feb 2023 14:47:39 +0100 Subject: [PATCH 0465/1086] Move initialize directory --- src/components/aocs/initialize_gnss_receiver.cpp | 2 +- src/components/aocs/initialize_gyro_sensor.cpp | 2 +- src/components/aocs/initialize_magnetometer.cpp | 2 +- src/components/aocs/initialize_magnetorquer.cpp | 2 +- src/components/aocs/initialize_reaction_wheel.cpp | 2 +- src/components/aocs/initialize_star_sensor.cpp | 2 +- src/components/aocs/initialize_sun_sensor.cpp | 2 +- .../base/initialize_sensor_template_functions.hpp | 2 +- src/components/communication/antenna_radiation_pattern.cpp | 2 +- src/components/communication/initialize_antenna.cpp | 2 +- .../communication/initialize_ground_station_calculator.cpp | 2 +- .../ideal_components/initialize_force_generator.cpp | 2 +- .../ideal_components/initialize_torque_generator.cpp | 2 +- src/components/mission/initialize_telescope.cpp | 2 +- src/components/power/csv_scenario_interface.cpp | 2 +- src/components/power/initialize_battery.cpp | 2 +- src/components/power/initialize_pcu_initial_study.cpp | 2 +- src/components/power/initialize_solar_array_panel.cpp | 2 +- src/components/propulsion/initialize_simple_thruster.cpp | 2 +- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- src/dynamics/attitude/initialize_attitude.cpp | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/thermal/initialize_node.cpp | 2 +- src/dynamics/thermal/initialize_temperature.cpp | 2 +- src/environment/global/global_environment.cpp | 2 +- src/environment/global/initialize_global_environment.cpp | 2 +- src/environment/global/initialize_gnss_satellites.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/environment/local/initialize_local_environment.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/interface/CMakeLists.txt | 1 - src/interface/log_output/initialize_log.cpp | 2 +- src/interface/sils/ports/power_port.cpp | 2 +- src/library/CMakeLists.txt | 2 ++ .../initialize/initialize_file_access.cpp | 0 .../initialize/initialize_file_access.hpp | 6 +++--- src/simulation/case/simulation_case.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- .../sample_ground_station_components.cpp | 2 +- .../initialize_monte_carlo_simulation.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- .../spacecraft/structure/initialize_structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.cpp | 2 +- 44 files changed, 45 insertions(+), 44 deletions(-) rename src/{interface => library}/initialize/initialize_file_access.cpp (100%) rename src/{interface => library}/initialize/initialize_file_access.hpp (96%) diff --git a/src/components/aocs/initialize_gnss_receiver.cpp b/src/components/aocs/initialize_gnss_receiver.cpp index 741cf769c..ca9ba6672 100644 --- a/src/components/aocs/initialize_gnss_receiver.cpp +++ b/src/components/aocs/initialize_gnss_receiver.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" typedef struct _gnssrecever_param { int prescaler; diff --git a/src/components/aocs/initialize_gyro_sensor.cpp b/src/components/aocs/initialize_gyro_sensor.cpp index 49e59dad0..10672f0fc 100644 --- a/src/components/aocs/initialize_gyro_sensor.cpp +++ b/src/components/aocs/initialize_gyro_sensor.cpp @@ -4,7 +4,7 @@ */ #include "initialize_gyro_sensor.hpp" -#include +#include #include "../base/initialize_sensor.hpp" diff --git a/src/components/aocs/initialize_magnetometer.cpp b/src/components/aocs/initialize_magnetometer.cpp index 959c62b56..7a70dcf89 100644 --- a/src/components/aocs/initialize_magnetometer.cpp +++ b/src/components/aocs/initialize_magnetometer.cpp @@ -5,7 +5,7 @@ #include "initialize_magnetometer.hpp" #include "../base/initialize_sensor.hpp" -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { IniAccess magsensor_conf(fname); diff --git a/src/components/aocs/initialize_magnetorquer.cpp b/src/components/aocs/initialize_magnetorquer.cpp index 9da0a0196..4ffd6b076 100644 --- a/src/components/aocs/initialize_magnetorquer.cpp +++ b/src/components/aocs/initialize_magnetorquer.cpp @@ -4,7 +4,7 @@ */ #include "initialize_magnetorquer.hpp" -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env) { diff --git a/src/components/aocs/initialize_reaction_wheel.cpp b/src/components/aocs/initialize_reaction_wheel.cpp index a706c2687..31b14ecc5 100644 --- a/src/components/aocs/initialize_reaction_wheel.cpp +++ b/src/components/aocs/initialize_reaction_wheel.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" // In order to share processing among initialization functions, variables should also be shared. These variables have internal linkages and cannot be // referenced from the outside. diff --git a/src/components/aocs/initialize_star_sensor.cpp b/src/components/aocs/initialize_star_sensor.cpp index 19466edd2..e328a029f 100644 --- a/src/components/aocs/initialize_star_sensor.cpp +++ b/src/components/aocs/initialize_star_sensor.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" using namespace std; diff --git a/src/components/aocs/initialize_sun_sensor.cpp b/src/components/aocs/initialize_sun_sensor.cpp index 130abe57e..0488b67d6 100644 --- a/src/components/aocs/initialize_sun_sensor.cpp +++ b/src/components/aocs/initialize_sun_sensor.cpp @@ -8,7 +8,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) { diff --git a/src/components/base/initialize_sensor_template_functions.hpp b/src/components/base/initialize_sensor_template_functions.hpp index f0925f032..3d7dcd2b6 100644 --- a/src/components/base/initialize_sensor_template_functions.hpp +++ b/src/components/base/initialize_sensor_template_functions.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ #define S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" template SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, diff --git a/src/components/communication/antenna_radiation_pattern.cpp b/src/components/communication/antenna_radiation_pattern.cpp index 999876691..e1812fe0f 100644 --- a/src/components/communication/antenna_radiation_pattern.cpp +++ b/src/components/communication/antenna_radiation_pattern.cpp @@ -6,7 +6,7 @@ #include "antenna_radiation_pattern.hpp" #include -#include +#include #include AntennaRadiationPattern::AntennaRadiationPattern() { gain_dBi_.assign(length_theta_, std::vector(length_phi_, 0.0)); } diff --git a/src/components/communication/initialize_antenna.cpp b/src/components/communication/initialize_antenna.cpp index 6a7dd5575..f65d468ed 100644 --- a/src/components/communication/initialize_antenna.cpp +++ b/src/components/communication/initialize_antenna.cpp @@ -10,7 +10,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" using libra::Vector; diff --git a/src/components/communication/initialize_ground_station_calculator.cpp b/src/components/communication/initialize_ground_station_calculator.cpp index 149fca923..f9f7a22f3 100644 --- a/src/components/communication/initialize_ground_station_calculator.cpp +++ b/src/components/communication/initialize_ground_station_calculator.cpp @@ -8,7 +8,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" GScalculator InitGScalculator(const std::string fname) { IniAccess gs_conf(fname); diff --git a/src/components/ideal_components/initialize_force_generator.cpp b/src/components/ideal_components/initialize_force_generator.cpp index 1f9bf19ac..1e7df7cd9 100644 --- a/src/components/ideal_components/initialize_force_generator.cpp +++ b/src/components/ideal_components/initialize_force_generator.cpp @@ -4,7 +4,7 @@ */ #include "initialize_force_generator.hpp" -#include +#include ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/components/ideal_components/initialize_torque_generator.cpp b/src/components/ideal_components/initialize_torque_generator.cpp index 1e8630497..d6798da4c 100644 --- a/src/components/ideal_components/initialize_torque_generator.cpp +++ b/src/components/ideal_components/initialize_torque_generator.cpp @@ -4,7 +4,7 @@ */ #include "initialize_torque_generator.hpp" -#include +#include TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { // General diff --git a/src/components/mission/initialize_telescope.cpp b/src/components/mission/initialize_telescope.cpp index 44dd1eeda..d57f743df 100644 --- a/src/components/mission/initialize_telescope.cpp +++ b/src/components/mission/initialize_telescope.cpp @@ -9,7 +9,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" using namespace std; diff --git a/src/components/power/csv_scenario_interface.cpp b/src/components/power/csv_scenario_interface.cpp index 8f898f78b..732fc0452 100644 --- a/src/components/power/csv_scenario_interface.cpp +++ b/src/components/power/csv_scenario_interface.cpp @@ -5,7 +5,7 @@ #include "csv_scenario_interface.hpp" -#include +#include bool CsvScenarioInterface::is_csv_senario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; diff --git a/src/components/power/initialize_battery.cpp b/src/components/power/initialize_battery.cpp index 360046bdb..d0db603f0 100644 --- a/src/components/power/initialize_battery.cpp +++ b/src/components/power/initialize_battery.cpp @@ -8,7 +8,7 @@ #include #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time) { IniAccess bat_conf(fname); diff --git a/src/components/power/initialize_pcu_initial_study.cpp b/src/components/power/initialize_pcu_initial_study.cpp index 7660e81e3..1bda59acb 100644 --- a/src/components/power/initialize_pcu_initial_study.cpp +++ b/src/components/power/initialize_pcu_initial_study.cpp @@ -9,7 +9,7 @@ #include #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time) { diff --git a/src/components/power/initialize_solar_array_panel.cpp b/src/components/power/initialize_solar_array_panel.cpp index dd9da7003..d2bf85ea8 100644 --- a/src/components/power/initialize_solar_array_panel.cpp +++ b/src/components/power/initialize_solar_array_panel.cpp @@ -7,7 +7,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { diff --git a/src/components/propulsion/initialize_simple_thruster.cpp b/src/components/propulsion/initialize_simple_thruster.cpp index a7d3ca39b..e3cd4ef8e 100644 --- a/src/components/propulsion/initialize_simple_thruster.cpp +++ b/src/components/propulsion/initialize_simple_thruster.cpp @@ -6,7 +6,7 @@ #include -#include "interface/initialize/initialize_file_access.hpp" +#include "library/initialize/initialize_file_access.hpp" SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 84412025f..9dca032db 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -5,7 +5,7 @@ #include "disturbances.hpp" -#include +#include #include "air_drag.hpp" #include "geopotential.hpp" diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index b658e98de..481494746 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -5,7 +5,7 @@ #include "initialize_disturbances.hpp" -#include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 75befde2f..22277a2a6 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -4,7 +4,7 @@ */ #include "initialize_attitude.hpp" -#include +#include Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, const Matrix<3, 3> inertia_tensor, const int sat_id) { diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 86244a2e7..d11261ee6 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -4,7 +4,7 @@ */ #include "initialize_orbit.hpp" -#include +#include #include "encke_orbit_propagation.hpp" #include "kepler_orbit_propagation.hpp" diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index 465f731f8..cbf26ecb2 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -5,8 +5,8 @@ #include "initialize_node.hpp" -#include #include +#include #include #include #include diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 90ef6a15f..4cac21c36 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -6,7 +6,7 @@ #include "initialize_temperature.hpp" #include -#include +#include #include #include "initialize_node.hpp" diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 0e284c5f7..c93c336c9 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -5,7 +5,7 @@ #include "global_environment.hpp" -#include +#include #include "initialize_global_environment.hpp" #include "initialize_gnss_satellites.hpp" diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 23713400c..d59d1263e 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #define CALC_LABEL "calculation" #define LOG_LABEL "logging" diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index 5ebf81f06..ff88fadac 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -5,8 +5,8 @@ #include "initialize_gnss_satellites.hpp" -#include #include +#include #include std::string return_dirctory_path(std::string sort) { diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 37b837119..47509e316 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -7,7 +7,7 @@ #include -#include +#include #include #include #include diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index e9a0f646f..2ac79f67c 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -5,7 +5,7 @@ #include "initialize_local_environment.hpp" -#include +#include #include #define CALC_LABEL "calculation" diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 6bc90238e..3f5240cc5 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -6,7 +6,7 @@ #include #include -#include +#include #include "initialize_local_environment.hpp" diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index cd26fcb28..4174c4e97 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -2,7 +2,6 @@ project(INTERFACE_) # INTERFACEだけだとCMakeの予約後に引っかかっ cmake_minimum_required(VERSION 3.13) set(SOURCE_FILES - initialize/initialize_file_access.cpp log_output/logger.cpp log_output/initialize_log.cpp diff --git a/src/interface/log_output/initialize_log.cpp b/src/interface/log_output/initialize_log.cpp index fdab0cd32..5bf20637f 100644 --- a/src/interface/log_output/initialize_log.cpp +++ b/src/interface/log_output/initialize_log.cpp @@ -5,7 +5,7 @@ #include "initialize_log.hpp" -#include +#include Logger* InitLog(std::string file_name) { IniAccess ini_file(file_name); diff --git a/src/interface/sils/ports/power_port.cpp b/src/interface/sils/ports/power_port.cpp index d3246c81a..0fe84a373 100644 --- a/src/interface/sils/ports/power_port.cpp +++ b/src/interface/sils/ports/power_port.cpp @@ -6,7 +6,7 @@ #include "power_port.hpp" #include -#include +#include PowerPort::PowerPort() : kPortId(-1), current_limit_(10.0), minimum_voltage_(3.3), assumed_power_consumption_(0.0) { is_on_ = true; // power on to work the component diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index bc93d68aa..84f8e4a42 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -4,6 +4,8 @@ cmake_minimum_required(VERSION 3.13) add_library(${PROJECT_NAME} STATIC geodesy/geodetic_position.cpp + initialize/initialize_file_access.cpp + randomization/global_randomization.cpp randomization/normal_randomization.cpp randomization/minimal_standard_linear_congruential_generator.cpp diff --git a/src/interface/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp similarity index 100% rename from src/interface/initialize/initialize_file_access.cpp rename to src/library/initialize/initialize_file_access.cpp diff --git a/src/interface/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp similarity index 96% rename from src/interface/initialize/initialize_file_access.hpp rename to src/library/initialize/initialize_file_access.hpp index aa9d0f4df..a524f0f39 100644 --- a/src/interface/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -3,8 +3,8 @@ * @brief Class to read and get parameters for the `ini` format file */ -#ifndef S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ -#define S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ +#ifndef S2E_LIBRARY_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ +#define S2E_LIBRARY_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ #define _CRT_SECURE_NO_WARNINGS @@ -169,4 +169,4 @@ void IniAccess::ReadVector(const char* section_name, const char* key_name, Vecto } } -#endif // S2E_INTERFACE_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ +#endif // S2E_LIBRARY_INITIALIZE_INITIALIZE_FILE_ACCESS_HPP_ diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 1c55ad864..373e465db 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -5,8 +5,8 @@ #include "simulation_case.hpp" -#include #include +#include #include SimulationCase::SimulationCase(std::string ini_base) { diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index e1065ca67..26c719b15 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,9 +6,9 @@ #include "ground_station.hpp" #include -#include #include #include +#include #include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 34c7a674c..228a318e7 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -4,7 +4,7 @@ */ #include "sample_ground_station_components.hpp" -#include +#include SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { IniAccess iniAccess = IniAccess(config_->gs_file_); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index c774813a0..a3ebc82aa 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -6,7 +6,7 @@ #include "initialize_monte_carlo_simulation.hpp" #include -#include +#include #define MAX_CHAR_NUM 256 diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 1c4b5bfd3..b3db1f800 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -5,7 +5,7 @@ #include "sample_components.hpp" -#include +#include #include "sample_port_configuration.hpp" diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index d7a103290..a7fe90bd7 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -5,7 +5,7 @@ #include "initialize_structure.hpp" -#include +#include #include #define MIN_VAL 1e-6 diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index b953fb912..25214c210 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -5,7 +5,7 @@ #include "structure.hpp" -#include +#include #include Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } From dc606d04a21e35c6478c02b1870ab8136320b26d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 14:54:41 +0100 Subject: [PATCH 0466/1086] Move log_output --- src/components/aocs/gnss_receiver.hpp | 2 +- src/components/aocs/gyro_sensor.hpp | 2 +- src/components/aocs/magnetometer.hpp | 2 +- src/components/aocs/magnetorquer.cpp | 2 +- src/components/aocs/magnetorquer.hpp | 2 +- src/components/aocs/reaction_wheel.hpp | 4 ++-- src/components/aocs/star_sensor.cpp | 2 +- src/components/aocs/star_sensor.hpp | 2 +- src/components/aocs/sun_sensor.cpp | 2 +- src/components/aocs/sun_sensor.hpp | 2 +- .../communication/ground_station_calculator.hpp | 2 +- src/components/examples/example_change_structure.hpp | 2 +- src/components/ideal_components/force_generator.hpp | 2 +- src/components/ideal_components/torque_generator.hpp | 2 +- src/components/mission/telescope.hpp | 2 +- src/components/power/battery.hpp | 2 +- src/components/power/pcu_initial_study.hpp | 2 +- src/components/power/power_control_unit.hpp | 2 +- src/components/power/solar_array_panel.hpp | 2 +- src/components/propulsion/simple_thruster.hpp | 2 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/geopotential.hpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/gravity_gradient.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/solar_radiation_pressure_disturbance.hpp | 2 +- src/disturbances/third_body_gravity.hpp | 2 +- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 2 +- src/dynamics/thermal/node.hpp | 2 +- src/dynamics/thermal/temperature.hpp | 2 +- src/environment/global/celestial_information.cpp | 2 +- src/environment/global/celestial_information.hpp | 2 +- src/environment/global/celestial_rotation.hpp | 2 +- src/environment/global/global_environment.hpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- src/environment/global/gnss_satellites.hpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 2 +- src/environment/global/simulation_time.hpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/atmosphere.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- .../local/solar_radiation_pressure_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 2 +- src/interface/CMakeLists.txt | 3 --- src/library/CMakeLists.txt | 3 +++ .../log_output => library/logger}/initialize_log.cpp | 0 .../log_output => library/logger}/initialize_log.hpp | 8 ++++---- .../log_output => library/logger}/log_utility.hpp | 6 +++--- src/{interface/log_output => library/logger}/loggable.hpp | 6 +++--- src/{interface/log_output => library/logger}/logger.cpp | 0 src/{interface/log_output => library/logger}/logger.hpp | 6 +++--- src/relative_information/relative_information.hpp | 4 ++-- src/s2e.cpp | 2 +- src/simulation/case/simulation_case.cpp | 2 +- src/simulation/case/simulation_case.hpp | 2 +- src/simulation/ground_station/ground_station.cpp | 4 ++-- src/simulation/simulation_configuration.hpp | 2 +- src/simulation/spacecraft/installed_components.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- 68 files changed, 80 insertions(+), 80 deletions(-) rename src/{interface/log_output => library/logger}/initialize_log.cpp (100%) rename src/{interface/log_output => library/logger}/initialize_log.hpp (70%) rename src/{interface/log_output => library/logger}/log_utility.hpp (96%) rename src/{interface/log_output => library/logger}/loggable.hpp (84%) rename src/{interface/log_output => library/logger}/logger.cpp (100%) rename src/{interface/log_output => library/logger}/logger.hpp (96%) diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/aocs/gnss_receiver.hpp index 66455c54b..860950c91 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/aocs/gnss_receiver.hpp @@ -9,7 +9,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/aocs/gyro_sensor.hpp index 1decc4a1d..48392abcc 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/aocs/gyro_sensor.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ #include -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/aocs/magnetometer.hpp b/src/components/aocs/magnetometer.hpp index 2da001925..75419b9fa 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/aocs/magnetometer.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ #include -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/aocs/magnetorquer.cpp index 3d4efcc1f..4b407337d 100644 --- a/src/components/aocs/magnetorquer.cpp +++ b/src/components/aocs/magnetorquer.cpp @@ -5,7 +5,7 @@ #include "magnetorquer.hpp" -#include +#include #include #include #include diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/aocs/magnetorquer.hpp index d02e291f6..c87ab2b54 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/aocs/magnetorquer.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ #include -#include +#include #include #include #include diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/aocs/reaction_wheel.hpp index 603e72497..ac36c2214 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/aocs/reaction_wheel.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ #define S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ -#include -#include +#include +#include #include #include #include diff --git a/src/components/aocs/star_sensor.cpp b/src/components/aocs/star_sensor.cpp index 7f0f5afd6..c0364477c 100644 --- a/src/components/aocs/star_sensor.cpp +++ b/src/components/aocs/star_sensor.cpp @@ -6,7 +6,7 @@ #include "star_sensor.hpp" #include -#include +#include #include #include #include diff --git a/src/components/aocs/star_sensor.hpp b/src/components/aocs/star_sensor.hpp index 626e92b2e..7f1b324d6 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/aocs/star_sensor.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/aocs/sun_sensor.cpp index ad1b77cca..67a251b61 100644 --- a/src/components/aocs/sun_sensor.cpp +++ b/src/components/aocs/sun_sensor.cpp @@ -8,7 +8,7 @@ #include #include using libra::NormalRand; -#include +#include #include using namespace std; diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/aocs/sun_sensor.hpp index f461f3b1a..6050face7 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/aocs/sun_sensor.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/communication/ground_station_calculator.hpp index 92f14ea01..94e52f619 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/communication/ground_station_calculator.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 0f89abbc8..11c303f40 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_HPP_ #define S2E_COMPONENTS_EXAMPLES_EXAMPLE_CHANGE_STRUCTURE_HPP_ -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal_components/force_generator.hpp index 2689ec1ee..a995f6452 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal_components/force_generator.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal_components/torque_generator.hpp index a6be77b78..7868d3b0b 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal_components/torque_generator.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include diff --git a/src/components/mission/telescope.hpp b/src/components/mission/telescope.hpp index 289edff4a..0062b9d56 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/mission/telescope.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/src/components/power/battery.hpp b/src/components/power/battery.hpp index ffaccb4cd..cdad63fc8 100644 --- a/src/components/power/battery.hpp +++ b/src/components/power/battery.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_BATTERY_HPP_P_ #define S2E_COMPONENTS_POWER_BATTERY_HPP_P_ -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/power/pcu_initial_study.hpp index 6e81efcd2..89e7e7d15 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/power/pcu_initial_study.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ #define S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/power/power_control_unit.hpp b/src/components/power/power_control_unit.hpp index c83ba7add..8fae06c27 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/power/power_control_unit.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ #define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ -#include #include +#include #include #include "../base/component.hpp" diff --git a/src/components/power/solar_array_panel.hpp b/src/components/power/solar_array_panel.hpp index 6d6e520d4..93f72ea2d 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/power/solar_array_panel.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include "../base/component.hpp" diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/propulsion/simple_thruster.hpp index 6eded5ca1..c5dabe0d9 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/propulsion/simple_thruster.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ #include -#include +#include #include #include #include diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index ae46586fe..fa9600036 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/log_utility.hpp" +#include "../library/logger/log_utility.hpp" using namespace std; using namespace libra; diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 572d59e30..dc42a326b 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -10,7 +10,7 @@ #include #include "../environment/local/atmosphere.hpp" -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../library/math/quaternion.hpp" #include "../library/math/vector.hpp" #include "surface_force.hpp" diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 6e904a45a..225db1427 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -11,7 +11,7 @@ #include #include -#include "../interface/log_output/log_utility.hpp" +#include "../library/logger/log_utility.hpp" // #define DEBUG_GEOPOTENTIAL diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index f934350df..879fb3cad 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../library/math/matrix.hpp" #include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 23668b736..e3aebc3b6 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/log_utility.hpp" +#include "../library/logger/log_utility.hpp" using namespace std; diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 2bfacddd5..7e2663bc5 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -8,7 +8,7 @@ #include -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../library/math/matrix.hpp" #include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 5672e8490..09f948235 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -9,7 +9,7 @@ using libra::NormalRand; #include -#include "../interface/log_output/log_utility.hpp" +#include "../library/logger/log_utility.hpp" #include "../library/randomization/global_randomization.hpp" #include "../library/randomization/random_walk.hpp" diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 2ad262103..7d4afe2c7 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -11,7 +11,7 @@ #include "../library/math/vector.hpp" using libra::Vector; -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index fd3fb08bd..67fa63e60 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -7,7 +7,7 @@ #include -#include "../interface/log_output/log_utility.hpp" +#include "../library/logger/log_utility.hpp" SolarRadiation::SolarRadiation(const vector& surfaces, const Vector<3>& cg_b) : SurfaceForce(surfaces, cg_b) {} diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index aa7a8d9dd..599a8c91b 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../library/math/vector.hpp" #include "surface_force.hpp" using libra::Vector; diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 58ce78129..0d704a64b 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -10,7 +10,7 @@ #include #include -#include "../interface/log_output/loggable.hpp" +#include "../library/logger/loggable.hpp" #include "../library/math/vector.hpp" #include "acceleration_disturbance.hpp" diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 78cdbb38c..58e17ac8e 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -4,7 +4,7 @@ */ #include "attitude.hpp" -#include +#include Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { omega_b_rad_s_ = libra::Vector<3>(0.0); diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 6ab64bd06..d1a66264b 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ #define S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ -#include +#include #include #include #include diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 7ee95e785..1998ff286 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,7 +4,7 @@ */ #include "attitude_rk4.hpp" -#include +#include #include using namespace std; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 1b49a5f3d..4aa314c7f 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -4,7 +4,7 @@ */ #include "controlled_attitude.hpp" -#include +#include #include #include diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 45b187fc9..03152777a 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -18,8 +18,8 @@ using libra::Vector; #include #include -#include #include +#include /** * @enum OrbitPropagateMode diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index ee5eb96b1..1a429fb2a 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_NODE_HPP_ #define S2E_DYNAMICS_THERMAL_NODE_HPP_ -#include +#include #include #include diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 29bb929ee..7bed885f8 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -6,7 +6,7 @@ #ifndef S2E_DYNAMICS_THERMAL_TEMPERATURE_HPP_ #define S2E_DYNAMICS_THERMAL_TEMPERATURE_HPP_ -#include +#include #include #include diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index b46ccfd37..f9225634f 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -10,8 +10,8 @@ #include #include -#include #include +#include #include using namespace std; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 299dda45c..acfa89771 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -11,7 +11,7 @@ #include #include "celestial_rotation.hpp" -#include "interface/log_output/loggable.hpp" +#include "library/logger/loggable.hpp" #include "library/math/matrix.hpp" #include "library/math/matrix_vector.hpp" #include "library/math/quaternion.hpp" diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 8217fa5a3..bebadde02 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -11,7 +11,7 @@ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ #include -#include +#include #include #include #include diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 7167b519b..2ae00f1db 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ -#include +#include #include #include "celestial_information.hpp" diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index a70e53144..ef9048769 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -10,8 +10,8 @@ #include #include -#include #include +#include #include #include #include diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index b30a78ba0..31f840ebf 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -9,8 +9,8 @@ #include #include #include -#include #include +#include #include #include #include diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index ec0bb8807..b57c6c3c1 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,7 +6,7 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ -#include +#include #include #include #include diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 434796da2..812ac78bb 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -17,7 +17,7 @@ #include #include -#include +#include /** *@struct TimeState diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index d7853ff9d..fe522227e 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,7 +5,7 @@ #include "atmosphere.hpp" -#include +#include #include #include #include diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 62de695be..180591eac 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,8 +7,8 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ -#include #include +#include #include #include #include diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index d5c0ffee5..40fbed094 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -11,7 +11,7 @@ using libra::Vector; #include using libra::Quaternion; -#include +#include /** * @class MagEnvironment diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 8a1789728..6954dbc07 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -8,8 +8,8 @@ #include #include -#include #include +#include #include using namespace std; diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index c8a3ca836..21f74dad4 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -8,7 +8,7 @@ #include #include #include -#include +#include #include #include diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 732590e1d..2304dda9e 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -7,7 +7,7 @@ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ #include -#include +#include #include using libra::Vector; diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 4174c4e97..3cf6c3cb7 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -3,9 +3,6 @@ cmake_minimum_required(VERSION 3.13) set(SOURCE_FILES - log_output/logger.cpp - log_output/initialize_log.cpp - sils/ports/gpio_port.cpp sils/ports/power_port.cpp sils/ports/uart_port.cpp diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 84f8e4a42..07c45ac7a 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -6,6 +6,9 @@ add_library(${PROJECT_NAME} STATIC initialize/initialize_file_access.cpp + logger/logger.cpp + logger/initialize_log.cpp + randomization/global_randomization.cpp randomization/normal_randomization.cpp randomization/minimal_standard_linear_congruential_generator.cpp diff --git a/src/interface/log_output/initialize_log.cpp b/src/library/logger/initialize_log.cpp similarity index 100% rename from src/interface/log_output/initialize_log.cpp rename to src/library/logger/initialize_log.cpp diff --git a/src/interface/log_output/initialize_log.hpp b/src/library/logger/initialize_log.hpp similarity index 70% rename from src/interface/log_output/initialize_log.hpp rename to src/library/logger/initialize_log.hpp index 4a9557dde..4dd64a836 100644 --- a/src/interface/log_output/initialize_log.hpp +++ b/src/library/logger/initialize_log.hpp @@ -3,10 +3,10 @@ * @brief Initialize function for Log output */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ -#define S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ +#ifndef S2E_LIBRARY_LOGGER_INITIALIZE_LOG_HPP_ +#define S2E_LIBRARY_LOGGER_INITIALIZE_LOG_HPP_ -#include +#include /** * @fn InitLog @@ -23,4 +23,4 @@ Logger* InitLog(std::string file_name); */ Logger* InitLogMC(std::string file_name, bool enable); -#endif // S2E_INTERFACE_LOG_OUTPUT_INITIALIZE_LOG_HPP_ +#endif // S2E_LIBRARY_LOGGER_INITIALIZE_LOG_HPP_ diff --git a/src/interface/log_output/log_utility.hpp b/src/library/logger/log_utility.hpp similarity index 96% rename from src/interface/log_output/log_utility.hpp rename to src/library/logger/log_utility.hpp index c15c3a9c0..c6be4e191 100644 --- a/src/interface/log_output/log_utility.hpp +++ b/src/library/logger/log_utility.hpp @@ -3,8 +3,8 @@ * @brief Utility functions to support logging for users */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ -#define S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ +#ifndef S2E_LIBRARY_LOGGER_LOG_UTILITY_HPP_ +#define S2E_LIBRARY_LOGGER_LOG_UTILITY_HPP_ #include #include @@ -159,4 +159,4 @@ std::string WriteQuaternion(std::string name, std::string frame) { return str_tmp.str(); } -#endif // S2E_INTERFACE_LOG_OUTPUT_LOG_UTILITY_HPP_ +#endif // S2E_LIBRARY_LOGGER_LOG_UTILITY_HPP_ diff --git a/src/interface/log_output/loggable.hpp b/src/library/logger/loggable.hpp similarity index 84% rename from src/interface/log_output/loggable.hpp rename to src/library/logger/loggable.hpp index ec6da480d..b2ae0e9dd 100644 --- a/src/interface/log_output/loggable.hpp +++ b/src/library/logger/loggable.hpp @@ -3,8 +3,8 @@ * @brief Abstract class to manage logging */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ -#define S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ +#ifndef S2E_LIBRARY_LOGGER_LOGGABLE_HPP_ +#define S2E_LIBRARY_LOGGER_LOGGABLE_HPP_ #include @@ -34,4 +34,4 @@ class ILoggable { bool IsLogEnabled = true; //!< Log enable flag }; -#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGABLE_HPP_ +#endif // S2E_LIBRARY_LOGGER_LOGGABLE_HPP_ diff --git a/src/interface/log_output/logger.cpp b/src/library/logger/logger.cpp similarity index 100% rename from src/interface/log_output/logger.cpp rename to src/library/logger/logger.cpp diff --git a/src/interface/log_output/logger.hpp b/src/library/logger/logger.hpp similarity index 96% rename from src/interface/log_output/logger.hpp rename to src/library/logger/logger.hpp index c20644b06..f2ea71868 100644 --- a/src/interface/log_output/logger.hpp +++ b/src/library/logger/logger.hpp @@ -3,8 +3,8 @@ * @brief Class to manage log output file */ -#ifndef S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ -#define S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ +#ifndef S2E_LIBRARY_LOGGER_LOGGER_HPP_ +#define S2E_LIBRARY_LOGGER_LOGGER_HPP_ #define _CRT_SECURE_NO_WARNINGS @@ -130,4 +130,4 @@ void Logger::Enable(bool enable) { is_enabled_ = enable; } std::string Logger::GetLogPath() const { return directory_path_; } -#endif // S2E_INTERFACE_LOG_OUTPUT_LOGGER_HPP_ +#endif // S2E_LIBRARY_LOGGER_LOGGER_HPP_ diff --git a/src/relative_information/relative_information.hpp b/src/relative_information/relative_information.hpp index 865259952..74b113135 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/relative_information/relative_information.hpp @@ -9,8 +9,8 @@ #include #include "../dynamics/dynamics.hpp" -#include "../interface/log_output/loggable.hpp" -#include "../interface/log_output/logger.hpp" +#include "../library/logger/loggable.hpp" +#include "../library/logger/logger.hpp" /** * @class RelativeInformation diff --git a/src/s2e.cpp b/src/s2e.cpp index 4d0b58af1..0511763a9 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -15,7 +15,7 @@ #include // Simulator includes -#include "interface/log_output/logger.hpp" +#include "library/logger/logger.hpp" // Add custom include files #include "simulation/case/sample_case.hpp" diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 373e465db..684b079cb 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -5,8 +5,8 @@ #include "simulation_case.hpp" -#include #include +#include #include SimulationCase::SimulationCase(std::string ini_base) { diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index b96aaa2c7..4d1a2fb30 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -7,7 +7,7 @@ #define S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ #include -#include +#include #include #include "../simulation_configuration.hpp" diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 26c719b15..83a5ece75 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -6,9 +6,9 @@ #include "ground_station.hpp" #include -#include -#include #include +#include +#include #include #include #include diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index c54406b1e..2e6aaf036 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -9,7 +9,7 @@ #include #include -#include "../interface/log_output/logger.hpp" +#include "../library/logger/logger.hpp" /** * @struct SimulationConfig diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index aaa24e8ce..abb060320 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -6,7 +6,7 @@ #ifndef S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ #define S2E_SIMULATION_SPACECRAFT_INSTALLED_COMPONENTS_HPP_ -#include +#include #include /** diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 35837bf0f..0d13c53ca 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -5,8 +5,8 @@ #include "spacecraft.hpp" -#include -#include +#include +#include Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { Initialize(sim_config, glo_env, sat_id); From 4a081e571148aa6ad71610744f22a25bc88c6ffb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 14:59:09 +0100 Subject: [PATCH 0467/1086] Move ring_buffer --- src/interface/CMakeLists.txt | 3 +-- src/interface/sils/ports/uart_port.hpp | 2 +- src/library/CMakeLists.txt | 1 + .../sils/utility => library/utilities}/ring_buffer.cpp | 0 .../sils/utility => library/utilities}/ring_buffer.hpp | 6 +++--- 5 files changed, 6 insertions(+), 6 deletions(-) rename src/{interface/sils/utility => library/utilities}/ring_buffer.cpp (100%) rename src/{interface/sils/utility => library/utilities}/ring_buffer.hpp (88%) diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 3cf6c3cb7..57ecd6ea3 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -7,8 +7,7 @@ set(SOURCE_FILES sils/ports/power_port.cpp sils/ports/uart_port.cpp sils/ports/i2c_port.cpp - sils/utility/ring_buffer.cpp - + hils/hils_port_manager.cpp ) diff --git a/src/interface/sils/ports/uart_port.hpp b/src/interface/sils/ports/uart_port.hpp index fe0676d9c..fbf905663 100644 --- a/src/interface/sils/ports/uart_port.hpp +++ b/src/interface/sils/ports/uart_port.hpp @@ -6,7 +6,7 @@ #ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ #define S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ -#include "../utility/ring_buffer.hpp" +#include /** * @class SCIPort diff --git a/src/library/CMakeLists.txt b/src/library/CMakeLists.txt index 07c45ac7a..db7dfd07b 100644 --- a/src/library/CMakeLists.txt +++ b/src/library/CMakeLists.txt @@ -35,6 +35,7 @@ add_library(${PROJECT_NAME} STATIC utilities/endian.cpp utilities/slip.cpp utilities/quantization.cpp + utilities/ring_buffer.cpp ) include(../../common.cmake) diff --git a/src/interface/sils/utility/ring_buffer.cpp b/src/library/utilities/ring_buffer.cpp similarity index 100% rename from src/interface/sils/utility/ring_buffer.cpp rename to src/library/utilities/ring_buffer.cpp diff --git a/src/interface/sils/utility/ring_buffer.hpp b/src/library/utilities/ring_buffer.hpp similarity index 88% rename from src/interface/sils/utility/ring_buffer.hpp rename to src/library/utilities/ring_buffer.hpp index fb468face..d329e1ce1 100644 --- a/src/interface/sils/utility/ring_buffer.hpp +++ b/src/library/utilities/ring_buffer.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate ring buffer */ -#ifndef S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ -#define S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ +#ifndef S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ +#define S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ typedef unsigned char byte; @@ -52,4 +52,4 @@ class RingBuffer { int wp_; //!< Write pointer }; -#endif // S2E_INTERFACE_SILS_UTILITY_RING_BUFFER_HPP_ +#endif // S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ From 28ed142d572b052ac4f49a3def8f74a398a6dbff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 15:16:28 +0100 Subject: [PATCH 0468/1086] Move sils ports --- src/components/CMakeLists.txt | 4 ++++ src/components/base/component.hpp | 2 +- src/components/cdh/obc.hpp | 6 +++--- src/components/cdh/obc_c2a.hpp | 2 +- src/{interface/sils => components}/ports/gpio_port.cpp | 0 src/{interface/sils => components}/ports/gpio_port.hpp | 6 +++--- src/{interface/sils => components}/ports/i2c_port.cpp | 0 src/{interface/sils => components}/ports/i2c_port.hpp | 6 +++--- src/{interface/sils => components}/ports/power_port.cpp | 0 src/{interface/sils => components}/ports/power_port.hpp | 6 +++--- src/{interface/sils => components}/ports/uart_port.cpp | 0 src/{interface/sils => components}/ports/uart_port.hpp | 6 +++--- src/components/power/power_control_unit.hpp | 2 +- src/interface/CMakeLists.txt | 5 ----- 14 files changed, 22 insertions(+), 23 deletions(-) rename src/{interface/sils => components}/ports/gpio_port.cpp (100%) rename src/{interface/sils => components}/ports/gpio_port.hpp (88%) rename src/{interface/sils => components}/ports/i2c_port.cpp (100%) rename src/{interface/sils => components}/ports/i2c_port.hpp (96%) rename src/{interface/sils => components}/ports/power_port.cpp (100%) rename src/{interface/sils => components}/ports/power_port.hpp (96%) rename src/{interface/sils => components}/ports/uart_port.cpp (100%) rename src/{interface/sils => components}/ports/uart_port.hpp (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 24e290bc8..aaec8c901 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -60,6 +60,10 @@ add_library(${PROJECT_NAME} STATIC propulsion/simple_thruster.cpp propulsion/initialize_simple_thruster.cpp + ports/gpio_port.cpp + ports/power_port.cpp + ports/uart_port.cpp + ports/i2c_port.cpp ) include(../../common.cmake) diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index a7cfcbaa8..2c1aabf3e 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -6,8 +6,8 @@ #ifndef S2E_COMPONENTS_BASE_COMPONENT_HPP_ #define S2E_COMPONENTS_BASE_COMPONENT_HPP_ +#include #include -#include #include #include "interface_tickable.hpp" diff --git a/src/components/cdh/obc.hpp b/src/components/cdh/obc.hpp index ee3555f6c..2ef99b6a2 100644 --- a/src/components/cdh/obc.hpp +++ b/src/components/cdh/obc.hpp @@ -6,9 +6,9 @@ #ifndef S2E_COMPONENTS_CDH_OBC_HPP_ #define S2E_COMPONENTS_CDH_OBC_HPP_ -#include -#include -#include +#include +#include +#include #include #include "../base/component.hpp" diff --git a/src/components/cdh/obc_c2a.hpp b/src/components/cdh/obc_c2a.hpp index 84c6134f5..22526e380 100644 --- a/src/components/cdh/obc_c2a.hpp +++ b/src/components/cdh/obc_c2a.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_CDH_OBC_C2A_HPP_ #define S2E_COMPONENTS_CDH_OBC_C2A_HPP_ -#include +#include #include "obc.hpp" diff --git a/src/interface/sils/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp similarity index 100% rename from src/interface/sils/ports/gpio_port.cpp rename to src/components/ports/gpio_port.cpp diff --git a/src/interface/sils/ports/gpio_port.hpp b/src/components/ports/gpio_port.hpp similarity index 88% rename from src/interface/sils/ports/gpio_port.hpp rename to src/components/ports/gpio_port.hpp index e645a4fd9..8cd0c460f 100644 --- a/src/interface/sils/ports/gpio_port.hpp +++ b/src/components/ports/gpio_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate GPIO(General Purpose Input and Output) port */ -#ifndef S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ -#define S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_GPIO_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_GPIO_PORT_HPP_ #include @@ -51,4 +51,4 @@ class GPIOPort { bool hl_state_; //!< GPIO High/Low state }; -#endif // S2E_INTERFACE_SILS_PORTS_GPIO_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_GPIO_PORT_HPP_ diff --git a/src/interface/sils/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp similarity index 100% rename from src/interface/sils/ports/i2c_port.cpp rename to src/components/ports/i2c_port.cpp diff --git a/src/interface/sils/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp similarity index 96% rename from src/interface/sils/ports/i2c_port.hpp rename to src/components/ports/i2c_port.hpp index 6ce75949e..7af29dcf6 100644 --- a/src/interface/sils/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port */ -#ifndef S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ -#define S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_I2C_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_I2C_PORT_HPP_ #include @@ -109,4 +109,4 @@ class I2CPort { std::map, unsigned char> cmd_buffer_; }; -#endif // S2E_INTERFACE_SILS_PORTS_I2C_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_I2C_PORT_HPP_ diff --git a/src/interface/sils/ports/power_port.cpp b/src/components/ports/power_port.cpp similarity index 100% rename from src/interface/sils/ports/power_port.cpp rename to src/components/ports/power_port.cpp diff --git a/src/interface/sils/ports/power_port.hpp b/src/components/ports/power_port.hpp similarity index 96% rename from src/interface/sils/ports/power_port.hpp rename to src/components/ports/power_port.hpp index a1c72b112..cba13af2e 100644 --- a/src/interface/sils/ports/power_port.hpp +++ b/src/components/ports/power_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate electrical power port */ -#ifndef S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ -#define S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_POWER_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_POWER_PORT_HPP_ #include @@ -133,4 +133,4 @@ class PowerPort { void Initialize(void); }; -#endif // S2E_INTERFACE_SILS_PORTS_POWER_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_POWER_PORT_HPP_ diff --git a/src/interface/sils/ports/uart_port.cpp b/src/components/ports/uart_port.cpp similarity index 100% rename from src/interface/sils/ports/uart_port.cpp rename to src/components/ports/uart_port.cpp diff --git a/src/interface/sils/ports/uart_port.hpp b/src/components/ports/uart_port.hpp similarity index 94% rename from src/interface/sils/ports/uart_port.hpp rename to src/components/ports/uart_port.hpp index fbf905663..4fc73a682 100644 --- a/src/interface/sils/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate UART communication port */ -#ifndef S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ -#define S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_UART_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_UART_PORT_HPP_ #include @@ -79,4 +79,4 @@ class SCIPort { RingBuffer* txb_; //!< Transmit buffer (OBC -> Component) }; -#endif // S2E_INTERFACE_SILS_PORTS_UART_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_UART_PORT_HPP_ diff --git a/src/components/power/power_control_unit.hpp b/src/components/power/power_control_unit.hpp index 8fae06c27..17b0edb86 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/power/power_control_unit.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ #define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ -#include +#include #include #include diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 57ecd6ea3..472ae5060 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -2,11 +2,6 @@ project(INTERFACE_) # INTERFACEだけだとCMakeの予約後に引っかかっ cmake_minimum_required(VERSION 3.13) set(SOURCE_FILES - - sils/ports/gpio_port.cpp - sils/ports/power_port.cpp - sils/ports/uart_port.cpp - sils/ports/i2c_port.cpp hils/hils_port_manager.cpp ) From b12f9f49d63eadc7d4b2dfa3a6a7b44a141b6f8d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 15:31:26 +0100 Subject: [PATCH 0469/1086] Move hils ports --- src/components/CMakeLists.txt | 120 ++++++++++-------- .../ports/hils_i2c_target_port.cpp | 0 .../ports/hils_i2c_target_port.hpp | 6 +- .../ports/hils_uart_port.cpp | 0 .../ports/hils_uart_port.hpp | 6 +- src/interface/CMakeLists.txt | 8 -- 6 files changed, 72 insertions(+), 68 deletions(-) rename src/{interface/hils => components}/ports/hils_i2c_target_port.cpp (100%) rename src/{interface/hils => components}/ports/hils_i2c_target_port.hpp (95%) rename src/{interface/hils => components}/ports/hils_uart_port.cpp (100%) rename src/{interface/hils => components}/ports/hils_uart_port.hpp (95%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index aaec8c901..f13570016 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -1,69 +1,81 @@ project(COMPONENT) cmake_minimum_required(VERSION 3.13) -add_library(${PROJECT_NAME} STATIC - base/component.cpp - base/uart_communication_with_obc.cpp - base/i2c_controller.cpp - base/i2c_target_communication_with_obc.cpp - base/gpio_connection_with_obc.cpp +set(SOURCE_FILES +base/component.cpp +base/uart_communication_with_obc.cpp +base/i2c_controller.cpp +base/i2c_target_communication_with_obc.cpp +base/gpio_connection_with_obc.cpp + +aocs/gyro_sensor.cpp +aocs/initialize_gyro_sensor.cpp +aocs/magnetometer.cpp +aocs/initialize_magnetometer.cpp +aocs/magnetorquer.cpp +aocs/initialize_magnetorquer.cpp +aocs/reaction_wheel_ode.cpp +aocs/reaction_wheel.cpp +aocs/initialize_reaction_wheel.cpp +aocs/reaction_wheel_jitter.cpp +aocs/star_sensor.cpp +aocs/initialize_star_sensor.cpp +aocs/sun_sensor.cpp +aocs/initialize_sun_sensor.cpp +aocs/gnss_receiver.cpp +aocs/initialize_gnss_receiver.cpp - aocs/gyro_sensor.cpp - aocs/initialize_gyro_sensor.cpp - aocs/magnetometer.cpp - aocs/initialize_magnetometer.cpp - aocs/magnetorquer.cpp - aocs/initialize_magnetorquer.cpp - aocs/reaction_wheel_ode.cpp - aocs/reaction_wheel.cpp - aocs/initialize_reaction_wheel.cpp - aocs/reaction_wheel_jitter.cpp - aocs/star_sensor.cpp - aocs/initialize_star_sensor.cpp - aocs/sun_sensor.cpp - aocs/initialize_sun_sensor.cpp - aocs/gnss_receiver.cpp - aocs/initialize_gnss_receiver.cpp +cdh/obc.cpp +cdh/obc_c2a.cpp - cdh/obc.cpp - cdh/obc_c2a.cpp +communication/antenna.cpp +communication/antenna_radiation_pattern.cpp +communication/initialize_antenna.cpp +communication/ground_station_calculator.cpp +communication/initialize_ground_station_calculator.cpp - communication/antenna.cpp - communication/antenna_radiation_pattern.cpp - communication/initialize_antenna.cpp - communication/ground_station_calculator.cpp - communication/initialize_ground_station_calculator.cpp +examples/example_change_structure.cpp +examples/example_serial_communication_with_obc.cpp +examples/example_serial_communication_for_hils.cpp +examples/example_i2c_controller_for_hils.cpp +examples/example_i2c_target_for_hils.cpp - examples/example_change_structure.cpp - examples/example_serial_communication_with_obc.cpp - examples/example_serial_communication_for_hils.cpp - examples/example_i2c_controller_for_hils.cpp - examples/example_i2c_target_for_hils.cpp +ideal_components/force_generator.cpp +ideal_components/initialize_force_generator.cpp +ideal_components/torque_generator.cpp +ideal_components/initialize_torque_generator.cpp - ideal_components/force_generator.cpp - ideal_components/initialize_force_generator.cpp - ideal_components/torque_generator.cpp - ideal_components/initialize_torque_generator.cpp +mission/telescope.cpp +mission/initialize_telescope.cpp - mission/telescope.cpp - mission/initialize_telescope.cpp +power/power_control_unit.cpp +power/battery.cpp +power/initialize_battery.cpp +power/pcu_initial_study.cpp +power/initialize_pcu_initial_study.cpp +power/solar_array_panel.cpp +power/initialize_solar_array_panel.cpp +power/csv_scenario_interface.cpp - power/power_control_unit.cpp - power/battery.cpp - power/initialize_battery.cpp - power/pcu_initial_study.cpp - power/initialize_pcu_initial_study.cpp - power/solar_array_panel.cpp - power/initialize_solar_array_panel.cpp - power/csv_scenario_interface.cpp +propulsion/simple_thruster.cpp +propulsion/initialize_simple_thruster.cpp - propulsion/simple_thruster.cpp - propulsion/initialize_simple_thruster.cpp +ports/gpio_port.cpp +ports/power_port.cpp +ports/uart_port.cpp +ports/i2c_port.cpp +) - ports/gpio_port.cpp - ports/power_port.cpp - ports/uart_port.cpp - ports/i2c_port.cpp +if(USE_HILS) + set(SOURCE_FILES + ${SOURCE_FILES} + hils/ports/hils_uart_port.cpp + hils/ports/hils_i2c_target_port.cpp + ) +endif() + +add_library(${PROJECT_NAME} STATIC + ${SOURCE_FILES} ) include(../../common.cmake) diff --git a/src/interface/hils/ports/hils_i2c_target_port.cpp b/src/components/ports/hils_i2c_target_port.cpp similarity index 100% rename from src/interface/hils/ports/hils_i2c_target_port.cpp rename to src/components/ports/hils_i2c_target_port.cpp diff --git a/src/interface/hils/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp similarity index 95% rename from src/interface/hils/ports/hils_i2c_target_port.hpp rename to src/components/ports/hils_i2c_target_port.hpp index 46d45ded4..7148c0b7b 100644 --- a/src/interface/hils/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -3,8 +3,8 @@ * @brief Class to control I2C-USB converter for the target(device) side from COM port */ -#ifndef S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ -#define S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_HILS_I2C_TARGET_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_HILS_I2C_TARGET_PORT_HPP_ #include @@ -107,4 +107,4 @@ class HilsI2cTargetPort : public HilsUartPort { std::map cmd_buffer_; }; -#endif // S2E_INTERFACE_HILS_PORTS_HILS_I2C_TARGET_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_HILS_I2C_TARGET_PORT_HPP_ diff --git a/src/interface/hils/ports/hils_uart_port.cpp b/src/components/ports/hils_uart_port.cpp similarity index 100% rename from src/interface/hils/ports/hils_uart_port.cpp rename to src/components/ports/hils_uart_port.cpp diff --git a/src/interface/hils/ports/hils_uart_port.hpp b/src/components/ports/hils_uart_port.hpp similarity index 95% rename from src/interface/hils/ports/hils_uart_port.hpp rename to src/components/ports/hils_uart_port.hpp index 32bb443e6..2dd520fcf 100644 --- a/src/interface/hils/ports/hils_uart_port.hpp +++ b/src/components/ports/hils_uart_port.hpp @@ -6,8 +6,8 @@ * @note TODO :We need to clarify the difference with ComPortInterface */ -#ifndef S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ -#define S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ +#ifndef S2E_COMPONENTS_PORTS_HILS_UART_PORT_HPP_ +#define S2E_COMPONENTS_PORTS_HILS_UART_PORT_HPP_ #include #include @@ -111,4 +111,4 @@ class HilsUartPort { int DiscardOutBuffer(); }; -#endif // S2E_INTERFACE_HILS_PORTS_HILS_UART_PORT_HPP_ +#endif // S2E_COMPONENTS_PORTS_HILS_UART_PORT_HPP_ diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt index 472ae5060..cb329520e 100644 --- a/src/interface/CMakeLists.txt +++ b/src/interface/CMakeLists.txt @@ -6,14 +6,6 @@ set(SOURCE_FILES hils/hils_port_manager.cpp ) -if(USE_HILS) - set(SOURCE_FILES - ${SOURCE_FILES} - hils/ports/hils_uart_port.cpp - hils/ports/hils_i2c_target_port.cpp - ) -endif() - add_library(${PROJECT_NAME} STATIC ${SOURCE_FILES} ) From cbe4a8f8b2433c7821024348fc9b0a364500da15 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 15:35:27 +0100 Subject: [PATCH 0470/1086] Move com port interface --- .../hils => library/communication}/com_port_interface.cpp | 0 .../hils => library/communication}/com_port_interface.hpp | 1 + 2 files changed, 1 insertion(+) rename src/{interface/hils => library/communication}/com_port_interface.cpp (100%) rename src/{interface/hils => library/communication}/com_port_interface.hpp (98%) diff --git a/src/interface/hils/com_port_interface.cpp b/src/library/communication/com_port_interface.cpp similarity index 100% rename from src/interface/hils/com_port_interface.cpp rename to src/library/communication/com_port_interface.cpp diff --git a/src/interface/hils/com_port_interface.hpp b/src/library/communication/com_port_interface.hpp similarity index 98% rename from src/interface/hils/com_port_interface.hpp rename to src/library/communication/com_port_interface.hpp index e53587f3a..57657fd2f 100644 --- a/src/interface/hils/com_port_interface.hpp +++ b/src/library/communication/com_port_interface.hpp @@ -2,6 +2,7 @@ * @file com_port_interface.hpp * @brief Class to manage PC's COM port * @details Currently, this feature supports Windows Visual Studio only.(FIXME) + * @note This file is not included in the compile targets * Reference: https://docs.microsoft.com/ja-jp/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 */ From 075aac85d0d1da6b1df8edd1ae8c8adf9213e321 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 15:44:28 +0100 Subject: [PATCH 0471/1086] Move HILS port manager --- CMakeLists.txt | 5 +---- src/components/base/i2c_controller.hpp | 2 +- .../base/i2c_target_communication_with_obc.hpp | 2 +- src/components/base/uart_communication_with_obc.hpp | 2 +- src/interface/CMakeLists.txt | 13 ------------- src/simulation/CMakeLists.txt | 2 ++ .../hils/hils_port_manager.cpp | 0 .../hils/hils_port_manager.hpp | 6 +++--- .../sample_spacecraft/sample_components.hpp | 2 +- 9 files changed, 10 insertions(+), 24 deletions(-) delete mode 100644 src/interface/CMakeLists.txt rename src/{interface => simulation}/hils/hils_port_manager.cpp (100%) rename src/{interface => simulation}/hils/hils_port_manager.hpp (97%) diff --git a/CMakeLists.txt b/CMakeLists.txt index ad8bae148..83cbf5cde 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,7 +70,6 @@ add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/components) add_subdirectory(src/relative_information) -add_subdirectory(src/interface) add_subdirectory(src/library) set(SOURCE_FILES @@ -140,7 +139,7 @@ endif() #target_link_libraries(${PROJECT_NAME} ${NRLMSISE00_LIB}) # Initialize link -target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT INTERFACE_ RELATIVE_INFO LIBRARY) +target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT RELATIVE_INFO LIBRARY) target_link_libraries(DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SIMULATION LIBRARY) target_link_libraries(DISTURBANCE DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT LIBRARY) target_link_libraries(SIMULATION DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT DISTURBANCE LIBRARY) @@ -153,7 +152,6 @@ target_link_libraries(${PROJECT_NAME} DISTURBANCE) target_link_libraries(${PROJECT_NAME} SIMULATION) target_link_libraries(${PROJECT_NAME} GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT) target_link_libraries(${PROJECT_NAME} RELATIVE_INFO) -target_link_libraries(${PROJECT_NAME} INTERFACE_) target_link_libraries(${PROJECT_NAME} COMPONENT) ## C2A integration @@ -171,7 +169,6 @@ if(USE_HILS) set_target_properties(SIMULATION PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(GLOBAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(LOCAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") - set_target_properties(INTERFACE_ PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(RELATIVE_INFO PROPERTIES COMMON_LANGUAGE_RUNTIME "") endif() diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index aa25b6a7a..1b1d21c0b 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_I2C_CONTROLLER_HPP_ #define S2E_COMPONENTS_BASE_I2C_CONTROLLER_HPP_ -#include "../../interface/hils/hils_port_manager.hpp" +#include "../../simulation/hils/hils_port_manager.hpp" #include "uart_communication_with_obc.hpp" /** diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 27be4d61c..d130ea38d 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ #define S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ -#include "../../interface/hils/hils_port_manager.hpp" +#include "../../simulation/hils/hils_port_manager.hpp" #include "../cdh/obc.hpp" #include "uart_communication_with_obc.hpp" diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 990b11319..5869ace96 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -6,7 +6,7 @@ #ifndef S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ #define S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ -#include +#include #include "../cdh/obc.hpp" diff --git a/src/interface/CMakeLists.txt b/src/interface/CMakeLists.txt deleted file mode 100644 index cb329520e..000000000 --- a/src/interface/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -project(INTERFACE_) # INTERFACEだけだとCMakeの予約後に引っかかってしまうよう -cmake_minimum_required(VERSION 3.13) - -set(SOURCE_FILES - - hils/hils_port_manager.cpp -) - -add_library(${PROJECT_NAME} STATIC - ${SOURCE_FILES} -) - -include(../../common.cmake) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 0d90aa9ef..4e645f368 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -20,6 +20,8 @@ add_library(${PROJECT_NAME} STATIC ground_station/ground_station.cpp inter_spacecraft_communication/inter_spacecraft_communication.cpp + + hils/hils_port_manager.cpp ) include(../../common.cmake) diff --git a/src/interface/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp similarity index 100% rename from src/interface/hils/hils_port_manager.cpp rename to src/simulation/hils/hils_port_manager.cpp diff --git a/src/interface/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp similarity index 97% rename from src/interface/hils/hils_port_manager.hpp rename to src/simulation/hils/hils_port_manager.hpp index 5b20ae5cd..e058a0d19 100644 --- a/src/interface/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -3,8 +3,8 @@ * @brief Class to manage COM ports for HILS test */ -#ifndef S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ -#define S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ +#ifndef S2E_SIMULATION_HILS_HILS_PORT_MANAGER_HPP_ +#define S2E_SIMULATION_HILS_HILS_PORT_MANAGER_HPP_ #ifdef USE_HILS #include "ports/hils_i2c_target_port.hpp" @@ -167,4 +167,4 @@ class HilsPortManager { #endif }; -#endif // S2E_INTERFACE_HILS_HILS_PORT_MANAGER_HPP_ +#endif // S2E_SIMULATION_HILS_HILS_PORT_MANAGER_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index c7e3969fc..b80c2b9bd 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -24,8 +24,8 @@ #include #include #include -#include #include +#include #include #include "../installed_components.hpp" From b2c68fb77eaf0a8fad2ecd58fe76e475da508d30 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 18:09:28 +0100 Subject: [PATCH 0472/1086] Rename inter spacecraft communication --- src/simulation/CMakeLists.txt | 2 +- .../inter_spacecraft_communication.cpp | 0 .../inter_spacecraft_communication.hpp | 6 +++--- 3 files changed, 4 insertions(+), 4 deletions(-) rename src/simulation/{inter_spacecraft_communication => multiple_spacecraft}/inter_spacecraft_communication.cpp (100%) rename src/simulation/{inter_spacecraft_communication => multiple_spacecraft}/inter_spacecraft_communication.hpp (63%) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index 0d90aa9ef..ef85e4605 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -19,7 +19,7 @@ add_library(${PROJECT_NAME} STATIC ground_station/ground_station.cpp - inter_spacecraft_communication/inter_spacecraft_communication.cpp + multiple_spacecraft/inter_spacecraft_communication.cpp ) include(../../common.cmake) diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp similarity index 100% rename from src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.cpp rename to src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp diff --git a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp similarity index 63% rename from src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp rename to src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp index 3e35dea15..49992e987 100644 --- a/src/simulation/inter_spacecraft_communication/inter_spacecraft_communication.hpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp @@ -3,8 +3,8 @@ * @brief Base class of inter satellite communication */ -#ifndef S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ -#define S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ +#ifndef S2E_SIMULATION_MULTIPLE_SPACECRAFT_INTER_SPACECRAFT_COMMUNICATION_HPP_ +#define S2E_SIMULATION_MULTIPLE_SPACECRAFT_INTER_SPACECRAFT_COMMUNICATION_HPP_ #include "../simulation_configuration.hpp" @@ -28,4 +28,4 @@ class InterSatComm { private: }; -#endif // S2E_SIMULATION_INTER_SPACECRAFT_COMMUNICATION_INTER_SPACECRAFT_COMMUNICATION_HPP_ +#endif // S2E_SIMULATION_MULTIPLE_SPACECRAFT_INTER_SPACECRAFT_COMMUNICATION_HPP_ From 0f18abf0af7fb8c79cf5ba708a21d68afe218b1b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 16 Feb 2023 18:16:53 +0100 Subject: [PATCH 0473/1086] Move relative information --- CMakeLists.txt | 5 +---- src/dynamics/dynamics.cpp | 2 +- src/dynamics/orbit/relative_orbit.hpp | 2 +- src/relative_information/CMakeLists.txt | 8 -------- src/simulation/CMakeLists.txt | 1 + .../multiple_spacecraft}/relative_information.cpp | 0 .../multiple_spacecraft}/relative_information.hpp | 12 ++++++------ src/simulation/spacecraft/spacecraft.hpp | 2 +- 8 files changed, 11 insertions(+), 21 deletions(-) delete mode 100644 src/relative_information/CMakeLists.txt rename src/{relative_information => simulation/multiple_spacecraft}/relative_information.cpp (100%) rename src/{relative_information => simulation/multiple_spacecraft}/relative_information.hpp (95%) diff --git a/CMakeLists.txt b/CMakeLists.txt index ad8bae148..2467fee5e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -69,7 +69,6 @@ add_subdirectory(src/environment/local) add_subdirectory(src/dynamics) add_subdirectory(src/disturbances) add_subdirectory(src/components) -add_subdirectory(src/relative_information) add_subdirectory(src/interface) add_subdirectory(src/library) @@ -140,7 +139,7 @@ endif() #target_link_libraries(${PROJECT_NAME} ${NRLMSISE00_LIB}) # Initialize link -target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT INTERFACE_ RELATIVE_INFO LIBRARY) +target_link_libraries(COMPONENT DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT INTERFACE_ LIBRARY) target_link_libraries(DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT SIMULATION LIBRARY) target_link_libraries(DISTURBANCE DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT LIBRARY) target_link_libraries(SIMULATION DYNAMICS GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT DISTURBANCE LIBRARY) @@ -152,7 +151,6 @@ target_link_libraries(${PROJECT_NAME} DYNAMICS) target_link_libraries(${PROJECT_NAME} DISTURBANCE) target_link_libraries(${PROJECT_NAME} SIMULATION) target_link_libraries(${PROJECT_NAME} GLOBAL_ENVIRONMENT LOCAL_ENVIRONMENT) -target_link_libraries(${PROJECT_NAME} RELATIVE_INFO) target_link_libraries(${PROJECT_NAME} INTERFACE_) target_link_libraries(${PROJECT_NAME} COMPONENT) @@ -172,7 +170,6 @@ if(USE_HILS) set_target_properties(GLOBAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(LOCAL_ENVIRONMENT PROPERTIES COMMON_LANGUAGE_RUNTIME "") set_target_properties(INTERFACE_ PROPERTIES COMMON_LANGUAGE_RUNTIME "") - set_target_properties(RELATIVE_INFO PROPERTIES COMMON_LANGUAGE_RUNTIME "") endif() ## GoogleTest settings diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index daf7b91a0..280a0c93e 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -5,7 +5,7 @@ #include "dynamics.hpp" -#include "../relative_information/relative_information.hpp" +#include "../simulation/multiple_spacecraft/relative_information.hpp" using namespace std; diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 7a6d7e841..ac07e0010 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include "orbit.hpp" diff --git a/src/relative_information/CMakeLists.txt b/src/relative_information/CMakeLists.txt deleted file mode 100644 index d09587d3c..000000000 --- a/src/relative_information/CMakeLists.txt +++ /dev/null @@ -1,8 +0,0 @@ -project(RELATIVE_INFO) -cmake_minimum_required(VERSION 3.13) - -add_library(${PROJECT_NAME} STATIC - relative_information.cpp -) - -include(../../common.cmake) diff --git a/src/simulation/CMakeLists.txt b/src/simulation/CMakeLists.txt index ef85e4605..ecc6a78d1 100644 --- a/src/simulation/CMakeLists.txt +++ b/src/simulation/CMakeLists.txt @@ -20,6 +20,7 @@ add_library(${PROJECT_NAME} STATIC ground_station/ground_station.cpp multiple_spacecraft/inter_spacecraft_communication.cpp + multiple_spacecraft/relative_information.cpp ) include(../../common.cmake) diff --git a/src/relative_information/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp similarity index 100% rename from src/relative_information/relative_information.cpp rename to src/simulation/multiple_spacecraft/relative_information.cpp diff --git a/src/relative_information/relative_information.hpp b/src/simulation/multiple_spacecraft/relative_information.hpp similarity index 95% rename from src/relative_information/relative_information.hpp rename to src/simulation/multiple_spacecraft/relative_information.hpp index 865259952..b19be4efe 100644 --- a/src/relative_information/relative_information.hpp +++ b/src/simulation/multiple_spacecraft/relative_information.hpp @@ -3,14 +3,14 @@ * @brief Base class to manage relative information between spacecraft */ -#ifndef S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ -#define S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ +#ifndef S2E_MULTIPLE_SPACECRAFT_RELATIVE_INFORMATION_HPP_ +#define S2E_MULTIPLE_SPACECRAFT_RELATIVE_INFORMATION_HPP_ #include -#include "../dynamics/dynamics.hpp" -#include "../interface/log_output/loggable.hpp" -#include "../interface/log_output/logger.hpp" +#include "../../dynamics/dynamics.hpp" +#include "../../interface/log_output/loggable.hpp" +#include "../../interface/log_output/logger.hpp" /** * @class RelativeInformation @@ -171,4 +171,4 @@ class RelativeInformation : public ILoggable { void ResizeLists(); }; -#endif // S2E_RELATIVE_INFORMATION_RELATIVE_INFORMATION_HPP_ +#endif // S2E_MULTIPLE_SPACECRAFT_RELATIVE_INFORMATION_HPP_ diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 7c6acccee..3d9b66cf3 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include "installed_components.hpp" #include "structure/structure.hpp" From 905dabfe108ad6b67aadce0b767c1fae1fd3a3e9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 05:44:48 +0100 Subject: [PATCH 0474/1086] Remove using --- src/disturbances/magnetic_disturbance.hpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 0edea76ff..2efd182e0 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -8,10 +8,8 @@ #include -#include "../library/math/vector.hpp" -using libra::Vector; - #include "../library/logger/loggable.hpp" +#include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" #include "simple_disturbance.hpp" From 0f771864faa61f01dd45b2ae17849bb31f4cb4a5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 14:48:49 +0100 Subject: [PATCH 0475/1086] Rename ideal components --- src/components/CMakeLists.txt | 8 ++++---- .../{ideal_components => ideal}/force_generator.cpp | 0 .../{ideal_components => ideal}/force_generator.hpp | 6 +++--- .../initialize_force_generator.cpp | 0 .../initialize_force_generator.hpp | 6 +++--- .../initialize_torque_generator.cpp | 0 .../initialize_torque_generator.hpp | 6 +++--- .../{ideal_components => ideal}/torque_generator.cpp | 0 .../{ideal_components => ideal}/torque_generator.hpp | 6 +++--- .../spacecraft/sample_spacecraft/sample_components.hpp | 4 ++-- 10 files changed, 18 insertions(+), 18 deletions(-) rename src/components/{ideal_components => ideal}/force_generator.cpp (100%) rename src/components/{ideal_components => ideal}/force_generator.hpp (95%) rename src/components/{ideal_components => ideal}/initialize_force_generator.cpp (100%) rename src/components/{ideal_components => ideal}/initialize_force_generator.hpp (68%) rename src/components/{ideal_components => ideal}/initialize_torque_generator.cpp (100%) rename src/components/{ideal_components => ideal}/initialize_torque_generator.hpp (68%) rename src/components/{ideal_components => ideal}/torque_generator.cpp (100%) rename src/components/{ideal_components => ideal}/torque_generator.hpp (94%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index f13570016..c27fd692f 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -40,10 +40,10 @@ examples/example_serial_communication_for_hils.cpp examples/example_i2c_controller_for_hils.cpp examples/example_i2c_target_for_hils.cpp -ideal_components/force_generator.cpp -ideal_components/initialize_force_generator.cpp -ideal_components/torque_generator.cpp -ideal_components/initialize_torque_generator.cpp +ideal/force_generator.cpp +ideal/initialize_force_generator.cpp +ideal/torque_generator.cpp +ideal/initialize_torque_generator.cpp mission/telescope.cpp mission/initialize_telescope.cpp diff --git a/src/components/ideal_components/force_generator.cpp b/src/components/ideal/force_generator.cpp similarity index 100% rename from src/components/ideal_components/force_generator.cpp rename to src/components/ideal/force_generator.cpp diff --git a/src/components/ideal_components/force_generator.hpp b/src/components/ideal/force_generator.hpp similarity index 95% rename from src/components/ideal_components/force_generator.hpp rename to src/components/ideal/force_generator.hpp index a995f6452..029461134 100644 --- a/src/components/ideal_components/force_generator.hpp +++ b/src/components/ideal/force_generator.hpp @@ -3,8 +3,8 @@ * @brief Ideal component which can generate force for control algorithm test */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ +#ifndef S2E_COMPONENTS_IDEAL_FORCE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_FORCE_GENERATOR_HPP_ #include #include @@ -115,4 +115,4 @@ class ForceGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_FORCE_GENERATOR_HPP_ +#endif // S2E_COMPONENTS_IDEAL_FORCE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/initialize_force_generator.cpp b/src/components/ideal/initialize_force_generator.cpp similarity index 100% rename from src/components/ideal_components/initialize_force_generator.cpp rename to src/components/ideal/initialize_force_generator.cpp diff --git a/src/components/ideal_components/initialize_force_generator.hpp b/src/components/ideal/initialize_force_generator.hpp similarity index 68% rename from src/components/ideal_components/initialize_force_generator.hpp rename to src/components/ideal/initialize_force_generator.hpp index 71b22e5eb..49d72f83d 100644 --- a/src/components/ideal_components/initialize_force_generator.hpp +++ b/src/components/ideal/initialize_force_generator.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for ForceGenerator */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ +#ifndef S2E_COMPONENTS_IDEAL_INITIALIZE_FORCE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_INITIALIZE_FORCE_GENERATOR_HPP_ #include "force_generator.hpp" @@ -17,4 +17,4 @@ */ ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_FORCE_GENERATOR_HPP_ +#endif // S2E_COMPONENTS_IDEAL_INITIALIZE_FORCE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/initialize_torque_generator.cpp b/src/components/ideal/initialize_torque_generator.cpp similarity index 100% rename from src/components/ideal_components/initialize_torque_generator.cpp rename to src/components/ideal/initialize_torque_generator.cpp diff --git a/src/components/ideal_components/initialize_torque_generator.hpp b/src/components/ideal/initialize_torque_generator.hpp similarity index 68% rename from src/components/ideal_components/initialize_torque_generator.hpp rename to src/components/ideal/initialize_torque_generator.hpp index 9272856f8..562f4694b 100644 --- a/src/components/ideal_components/initialize_torque_generator.hpp +++ b/src/components/ideal/initialize_torque_generator.hpp @@ -3,8 +3,8 @@ * @brief Initialize function for TorqueGenerator */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ +#ifndef S2E_COMPONENTS_IDEAL_INITIALIZE_TORQUE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_INITIALIZE_TORQUE_GENERATOR_HPP_ #include "torque_generator.hpp" @@ -17,4 +17,4 @@ */ TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_INITIALIZE_TORQUE_GENERATOR_HPP_ +#endif // S2E_COMPONENTS_IDEAL_INITIALIZE_TORQUE_GENERATOR_HPP_ diff --git a/src/components/ideal_components/torque_generator.cpp b/src/components/ideal/torque_generator.cpp similarity index 100% rename from src/components/ideal_components/torque_generator.cpp rename to src/components/ideal/torque_generator.cpp diff --git a/src/components/ideal_components/torque_generator.hpp b/src/components/ideal/torque_generator.hpp similarity index 94% rename from src/components/ideal_components/torque_generator.hpp rename to src/components/ideal/torque_generator.hpp index 7868d3b0b..7330c1d18 100644 --- a/src/components/ideal_components/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -3,8 +3,8 @@ * @brief Ideal component which can generate torque for control algorithm test */ -#ifndef S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ -#define S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ +#ifndef S2E_COMPONENTS_IDEAL_TORQUE_GENERATOR_HPP_ +#define S2E_COMPONENTS_IDEAL_TORQUE_GENERATOR_HPP_ #include #include @@ -93,4 +93,4 @@ class TorqueGenerator : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_IDEAL_COMPONENTS_TORQUE_GENERATOR_HPP_ +#endif // S2E_COMPONENTS_IDEAL_TORQUE_GENERATOR_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index b80c2b9bd..8642a941c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -19,8 +19,8 @@ #include #include #include -#include -#include +#include +#include #include #include #include From fed623dd23a5fdc40621537afe332e579bcacf3f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 14:49:47 +0100 Subject: [PATCH 0476/1086] Add products --- src/components/products/.gitkeep | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 src/components/products/.gitkeep diff --git a/src/components/products/.gitkeep b/src/components/products/.gitkeep new file mode 100644 index 000000000..e69de29bb From 7839e83b647744d262b2b3433e5f8912d459d804 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:19:20 +0100 Subject: [PATCH 0477/1086] Move cdh --- src/components/CMakeLists.txt | 4 ++-- src/components/aocs/gyro_sensor.cpp | 2 -- src/components/base/gpio_connection_with_obc.hpp | 2 +- .../base/i2c_target_communication_with_obc.hpp | 2 +- src/components/base/uart_communication_with_obc.hpp | 2 +- .../{cdh/obc.cpp => real/cdh/on_board_computer.cpp} | 4 ++-- .../{cdh/obc.hpp => real/cdh/on_board_computer.hpp} | 10 +++++----- .../cdh/on_board_computer_with_c2a.cpp} | 4 ++-- .../cdh/on_board_computer_with_c2a.hpp} | 10 +++++----- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 10 files changed, 20 insertions(+), 22 deletions(-) rename src/components/{cdh/obc.cpp => real/cdh/on_board_computer.cpp} (98%) rename src/components/{cdh/obc.hpp => real/cdh/on_board_computer.hpp} (97%) rename src/components/{cdh/obc_c2a.cpp => real/cdh/on_board_computer_with_c2a.cpp} (98%) rename src/components/{cdh/obc_c2a.hpp => real/cdh/on_board_computer_with_c2a.hpp} (98%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index c27fd692f..0e7b8a231 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -25,8 +25,8 @@ aocs/initialize_sun_sensor.cpp aocs/gnss_receiver.cpp aocs/initialize_gnss_receiver.cpp -cdh/obc.cpp -cdh/obc_c2a.cpp +real/cdh/on_board_computer.cpp +real/cdh/on_board_computer_with_c2a.cpp communication/antenna.cpp communication/antenna_radiation_pattern.cpp diff --git a/src/components/aocs/gyro_sensor.cpp b/src/components/aocs/gyro_sensor.cpp index a8fb285f0..bc1b822eb 100644 --- a/src/components/aocs/gyro_sensor.cpp +++ b/src/components/aocs/gyro_sensor.cpp @@ -5,8 +5,6 @@ #include "gyro_sensor.hpp" -#include "../cdh/obc_c2a.hpp" - Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) : ComponentBase(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index 81a4ab2ba..ab914d18d 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -7,7 +7,7 @@ #ifndef S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ #define S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ -#include "../cdh/obc.hpp" +#include "../real/cdh/on_board_computer.hpp" /** * @class ObcGpioBase diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index d130ea38d..fda5f51e2 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -7,7 +7,7 @@ #define S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ #include "../../simulation/hils/hils_port_manager.hpp" -#include "../cdh/obc.hpp" +#include "../real/cdh/on_board_computer.hpp" #include "uart_communication_with_obc.hpp" /** diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 5869ace96..8f2529ab0 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -8,7 +8,7 @@ #include -#include "../cdh/obc.hpp" +#include "../real/cdh/on_board_computer.hpp" /** * @enum OBC_COM_UART_MODE diff --git a/src/components/cdh/obc.cpp b/src/components/real/cdh/on_board_computer.cpp similarity index 98% rename from src/components/cdh/obc.cpp rename to src/components/real/cdh/on_board_computer.cpp index 9e0a18131..bda53a113 100644 --- a/src/components/cdh/obc.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -1,8 +1,8 @@ /* - * @file obc.cpp + * @file on_board_computer.cpp * @brief Class to emulate on board computer */ -#include "obc.hpp" +#include "on_board_computer.hpp" OBC::OBC(ClockGenerator* clock_gen) : ComponentBase(1, clock_gen) { Initialize(); } diff --git a/src/components/cdh/obc.hpp b/src/components/real/cdh/on_board_computer.hpp similarity index 97% rename from src/components/cdh/obc.hpp rename to src/components/real/cdh/on_board_computer.hpp index 2ef99b6a2..4264a91c6 100644 --- a/src/components/cdh/obc.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -1,17 +1,17 @@ /* - * @file obc.hpp + * @file on_board_computer.hpp * @brief Class to emulate on board computer */ -#ifndef S2E_COMPONENTS_CDH_OBC_HPP_ -#define S2E_COMPONENTS_CDH_OBC_HPP_ +#ifndef S2E_COMPONENTS_REAL_CDH_OBC_HPP_ +#define S2E_COMPONENTS_REAL_CDH_OBC_HPP_ #include #include #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" /* * @class OBC @@ -206,4 +206,4 @@ class OBC : public ComponentBase { std::map gpio_ports_; //!< GPIO ports }; -#endif // S2E_COMPONENTS_CDH_OBC_HPP_ +#endif // S2E_COMPONENTS_REAL_CDH_OBC_HPP_ diff --git a/src/components/cdh/obc_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp similarity index 98% rename from src/components/cdh/obc_c2a.cpp rename to src/components/real/cdh/on_board_computer_with_c2a.cpp index b565e4fe6..02282af39 100644 --- a/src/components/cdh/obc_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -1,9 +1,9 @@ /* - * @file obc_c2a.cpp + * @file on_board_computer_with_c2a.cpp * @brief Class to emulate on board computer with C2A flight software */ -#include "obc_c2a.hpp" +#include "on_board_computer_with_c2a.hpp" #ifdef USE_C2A #include "src_core/System/TaskManager/task_dispatcher.h" diff --git a/src/components/cdh/obc_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp similarity index 98% rename from src/components/cdh/obc_c2a.hpp rename to src/components/real/cdh/on_board_computer_with_c2a.hpp index 22526e380..a642ee710 100644 --- a/src/components/cdh/obc_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -1,14 +1,14 @@ /* - * @file obc_c2a.hpp + * @file on_board_computer_with_c2a.hpp * @brief Class to emulate on board computer with C2A flight software */ -#ifndef S2E_COMPONENTS_CDH_OBC_C2A_HPP_ -#define S2E_COMPONENTS_CDH_OBC_C2A_HPP_ +#ifndef S2E_COMPONENTS_REAL_CDH_OBC_C2A_HPP_ +#define S2E_COMPONENTS_REAL_CDH_OBC_C2A_HPP_ #include -#include "obc.hpp" +#include "on_board_computer.hpp" /* * @class OBC_C2A @@ -287,4 +287,4 @@ int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned int OBC_C2A_GpioWrite(int port_id, const bool is_high); bool OBC_C2A_GpioRead(int port_id); // return false when the port_id is not used -#endif // S2E_COMPONENTS_CDH_OBC_C2A_HPP_ +#endif // S2E_COMPONENTS_REAL_CDH_OBC_C2A_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 8642a941c..836fb655b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -13,7 +13,7 @@ #include #include #include -#include +#include #include #include #include From 76afd75088f8d53bb16c0bac9699959b9168a53f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:21:08 +0100 Subject: [PATCH 0478/1086] Move thermal --- src/components/{ => real}/thermal/.gitkeep | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename src/components/{ => real}/thermal/.gitkeep (100%) diff --git a/src/components/thermal/.gitkeep b/src/components/real/thermal/.gitkeep similarity index 100% rename from src/components/thermal/.gitkeep rename to src/components/real/thermal/.gitkeep From 42d362127375fda4db5cf112f514c82bcd0bbbfd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:26:46 +0100 Subject: [PATCH 0479/1086] Move propulsion --- src/components/CMakeLists.txt | 4 ++-- .../{ => real}/propulsion/initialize_simple_thruster.cpp | 0 .../{ => real}/propulsion/initialize_simple_thruster.hpp | 8 ++++---- src/components/{ => real}/propulsion/simple_thruster.cpp | 0 src/components/{ => real}/propulsion/simple_thruster.hpp | 8 ++++---- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 6 files changed, 11 insertions(+), 11 deletions(-) rename src/components/{ => real}/propulsion/initialize_simple_thruster.cpp (100%) rename src/components/{ => real}/propulsion/initialize_simple_thruster.hpp (82%) rename src/components/{ => real}/propulsion/simple_thruster.cpp (100%) rename src/components/{ => real}/propulsion/simple_thruster.hpp (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 0e7b8a231..b21410348 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -57,8 +57,8 @@ power/solar_array_panel.cpp power/initialize_solar_array_panel.cpp power/csv_scenario_interface.cpp -propulsion/simple_thruster.cpp -propulsion/initialize_simple_thruster.cpp +real/propulsion/simple_thruster.cpp +real/propulsion/initialize_simple_thruster.cpp ports/gpio_port.cpp ports/power_port.cpp diff --git a/src/components/propulsion/initialize_simple_thruster.cpp b/src/components/real/propulsion/initialize_simple_thruster.cpp similarity index 100% rename from src/components/propulsion/initialize_simple_thruster.cpp rename to src/components/real/propulsion/initialize_simple_thruster.cpp diff --git a/src/components/propulsion/initialize_simple_thruster.hpp b/src/components/real/propulsion/initialize_simple_thruster.hpp similarity index 82% rename from src/components/propulsion/initialize_simple_thruster.hpp rename to src/components/real/propulsion/initialize_simple_thruster.hpp index 55736928a..52f604077 100644 --- a/src/components/propulsion/initialize_simple_thruster.hpp +++ b/src/components/real/propulsion/initialize_simple_thruster.hpp @@ -3,10 +3,10 @@ * @brief Initialize function os SimpleThruster */ -#ifndef S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ -#define S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ +#ifndef S2E_COMPONENTS_REAL_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ +#define S2E_COMPONENTS_REAL_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ -#include +#include "simple_thruster.hpp" /** * @fn InitSimpleThruster @@ -32,4 +32,4 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ +#endif // S2E_COMPONENTS_REAL_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ diff --git a/src/components/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp similarity index 100% rename from src/components/propulsion/simple_thruster.cpp rename to src/components/real/propulsion/simple_thruster.cpp diff --git a/src/components/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp similarity index 96% rename from src/components/propulsion/simple_thruster.hpp rename to src/components/real/propulsion/simple_thruster.hpp index c5dabe0d9..af95e7ee7 100644 --- a/src/components/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -3,8 +3,8 @@ * @brief Component emulation of simple thruster */ -#ifndef S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ -#define S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ +#ifndef S2E_COMPONENTS_REAL_PROPULSION_SIMPLE_THRUSTER_HPP_ +#define S2E_COMPONENTS_REAL_PROPULSION_SIMPLE_THRUSTER_HPP_ #include #include @@ -13,7 +13,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" /* * @class SimpleThruster @@ -152,4 +152,4 @@ class SimpleThruster : public ComponentBase, public ILoggable { const Dynamics* dynamics_; //!< Spacecraft dynamics information }; -#endif // S2E_COMPONENTS_PROPULSION_SIMPLE_THRUSTER_HPP_ +#endif // S2E_COMPONENTS_REAL_PROPULSION_SIMPLE_THRUSTER_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 836fb655b..09da69085 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -22,7 +22,7 @@ #include #include #include -#include +#include #include #include #include From 99090871baa2c91f7bb8145f74941208d626ceb5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:31:54 +0100 Subject: [PATCH 0480/1086] Move mission --- src/components/CMakeLists.txt | 4 ++-- .../{ => real}/mission/initialize_telescope.cpp | 0 .../{ => real}/mission/initialize_telescope.hpp | 8 ++++---- src/components/{ => real}/mission/telescope.cpp | 0 src/components/{ => real}/mission/telescope.hpp | 6 +++--- 5 files changed, 9 insertions(+), 9 deletions(-) rename src/components/{ => real}/mission/initialize_telescope.cpp (100%) rename src/components/{ => real}/mission/initialize_telescope.hpp (75%) rename src/components/{ => real}/mission/telescope.cpp (100%) rename src/components/{ => real}/mission/telescope.hpp (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index b21410348..be228e606 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -45,8 +45,8 @@ ideal/initialize_force_generator.cpp ideal/torque_generator.cpp ideal/initialize_torque_generator.cpp -mission/telescope.cpp -mission/initialize_telescope.cpp +real/mission/telescope.cpp +real/mission/initialize_telescope.cpp power/power_control_unit.cpp power/battery.cpp diff --git a/src/components/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp similarity index 100% rename from src/components/mission/initialize_telescope.cpp rename to src/components/real/mission/initialize_telescope.cpp diff --git a/src/components/mission/initialize_telescope.hpp b/src/components/real/mission/initialize_telescope.hpp similarity index 75% rename from src/components/mission/initialize_telescope.hpp rename to src/components/real/mission/initialize_telescope.hpp index de01db35d..34696d601 100644 --- a/src/components/mission/initialize_telescope.hpp +++ b/src/components/real/mission/initialize_telescope.hpp @@ -3,10 +3,10 @@ * @brief Initialize function of Telescope */ -#ifndef S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ -#define S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ +#ifndef S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ +#define S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ -#include +#include "telescope.hpp" /* * @fn InitTelescope @@ -21,4 +21,4 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); -#endif // S2E_COMPONENTS_MISSION_INITIALIZE_TELESCOPE_HPP_ +#endif // S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/mission/telescope.cpp b/src/components/real/mission/telescope.cpp similarity index 100% rename from src/components/mission/telescope.cpp rename to src/components/real/mission/telescope.cpp diff --git a/src/components/mission/telescope.hpp b/src/components/real/mission/telescope.hpp similarity index 96% rename from src/components/mission/telescope.hpp rename to src/components/real/mission/telescope.hpp index 0062b9d56..cb27125ea 100644 --- a/src/components/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -3,8 +3,8 @@ * @brief Component emulation: Telescope */ -#ifndef S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ -#define S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ +#ifndef S2E_COMPONENTS_REAL_MISSION_TELESCOPE_HPP_P_ +#define S2E_COMPONENTS_REAL_MISSION_TELESCOPE_HPP_P_ #include #include @@ -123,4 +123,4 @@ class Telescope : public ComponentBase, public ILoggable { //************************************************************* }; -#endif // S2E_COMPONENTS_MISSION_TELESCOPE_HPP_P_ +#endif // S2E_COMPONENTS_REAL_MISSION_TELESCOPE_HPP_P_ From 6d704be8fa87081c9905d5129c83636e6ee20f1e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:41:48 +0100 Subject: [PATCH 0481/1086] Move power --- src/components/CMakeLists.txt | 16 ++++++++-------- src/components/{ => real}/power/battery.cpp | 0 src/components/{ => real}/power/battery.hpp | 8 ++++---- .../{ => real}/power/csv_scenario_interface.cpp | 0 .../{ => real}/power/csv_scenario_interface.hpp | 6 +++--- .../{ => real}/power/initialize_battery.cpp | 0 .../{ => real}/power/initialize_battery.hpp | 8 ++++---- .../power/initialize_pcu_initial_study.cpp | 0 .../power/initialize_pcu_initial_study.hpp | 8 ++++---- .../power/initialize_solar_array_panel.cpp | 0 .../power/initialize_solar_array_panel.hpp | 8 ++++---- .../{ => real}/power/pcu_initial_study.cpp | 2 +- .../{ => real}/power/pcu_initial_study.hpp | 8 ++++---- .../{ => real}/power/power_control_unit.cpp | 0 .../{ => real}/power/power_control_unit.hpp | 8 ++++---- .../{ => real}/power/solar_array_panel.cpp | 2 +- .../{ => real}/power/solar_array_panel.hpp | 8 ++++---- .../sample_spacecraft/sample_components.hpp | 2 +- 18 files changed, 42 insertions(+), 42 deletions(-) rename src/components/{ => real}/power/battery.cpp (100%) rename src/components/{ => real}/power/battery.hpp (96%) rename src/components/{ => real}/power/csv_scenario_interface.cpp (100%) rename src/components/{ => real}/power/csv_scenario_interface.hpp (92%) rename src/components/{ => real}/power/initialize_battery.cpp (100%) rename src/components/{ => real}/power/initialize_battery.hpp (65%) rename src/components/{ => real}/power/initialize_pcu_initial_study.cpp (100%) rename src/components/{ => real}/power/initialize_pcu_initial_study.hpp (71%) rename src/components/{ => real}/power/initialize_solar_array_panel.cpp (100%) rename src/components/{ => real}/power/initialize_solar_array_panel.hpp (80%) rename src/components/{ => real}/power/pcu_initial_study.cpp (98%) rename src/components/{ => real}/power/pcu_initial_study.hpp (91%) rename src/components/{ => real}/power/power_control_unit.cpp (100%) rename src/components/{ => real}/power/power_control_unit.hpp (92%) rename src/components/{ => real}/power/solar_array_panel.cpp (98%) rename src/components/{ => real}/power/solar_array_panel.hpp (96%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index be228e606..02aec3749 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -48,14 +48,14 @@ ideal/initialize_torque_generator.cpp real/mission/telescope.cpp real/mission/initialize_telescope.cpp -power/power_control_unit.cpp -power/battery.cpp -power/initialize_battery.cpp -power/pcu_initial_study.cpp -power/initialize_pcu_initial_study.cpp -power/solar_array_panel.cpp -power/initialize_solar_array_panel.cpp -power/csv_scenario_interface.cpp +real/power/power_control_unit.cpp +real/power/battery.cpp +real/power/initialize_battery.cpp +real/power/pcu_initial_study.cpp +real/power/initialize_pcu_initial_study.cpp +real/power/solar_array_panel.cpp +real/power/initialize_solar_array_panel.cpp +real/power/csv_scenario_interface.cpp real/propulsion/simple_thruster.cpp real/propulsion/initialize_simple_thruster.cpp diff --git a/src/components/power/battery.cpp b/src/components/real/power/battery.cpp similarity index 100% rename from src/components/power/battery.cpp rename to src/components/real/power/battery.cpp diff --git a/src/components/power/battery.hpp b/src/components/real/power/battery.hpp similarity index 96% rename from src/components/power/battery.hpp rename to src/components/real/power/battery.hpp index cdad63fc8..28f912fba 100644 --- a/src/components/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -3,13 +3,13 @@ * @brief Component emulation of battery */ -#ifndef S2E_COMPONENTS_POWER_BATTERY_HPP_P_ -#define S2E_COMPONENTS_POWER_BATTERY_HPP_P_ +#ifndef S2E_COMPONENTS_REAL_POWER_BATTERY_HPP_P_ +#define S2E_COMPONENTS_REAL_POWER_BATTERY_HPP_P_ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" /* * @class BAT @@ -132,4 +132,4 @@ class BAT : public ComponentBase, public ILoggable { void UpdateBatVoltage(); }; -#endif // S2E_COMPONENTS_POWER_BATTERY_HPP_P_ +#endif // S2E_COMPONENTS_REAL_POWER_BATTERY_HPP_P_ diff --git a/src/components/power/csv_scenario_interface.cpp b/src/components/real/power/csv_scenario_interface.cpp similarity index 100% rename from src/components/power/csv_scenario_interface.cpp rename to src/components/real/power/csv_scenario_interface.cpp diff --git a/src/components/power/csv_scenario_interface.hpp b/src/components/real/power/csv_scenario_interface.hpp similarity index 92% rename from src/components/power/csv_scenario_interface.hpp rename to src/components/real/power/csv_scenario_interface.hpp index 73b30008c..fbae784a9 100644 --- a/src/components/power/csv_scenario_interface.hpp +++ b/src/components/real/power/csv_scenario_interface.hpp @@ -3,8 +3,8 @@ * @brief Interface to read power related scenario in CSV file */ -#ifndef S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ -#define S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_CSV_SCENARIO_INTERFACE_HPP_ +#define S2E_COMPONENTS_REAL_POWER_CSV_SCENARIO_INTERFACE_HPP_ #include #include @@ -78,4 +78,4 @@ class CsvScenarioInterface { static std::map buffers_; //!< Buffer }; -#endif // S2E_COMPONENTS_POWER_CSV_SCENARIO_INTERFACE_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_CSV_SCENARIO_INTERFACE_HPP_ diff --git a/src/components/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp similarity index 100% rename from src/components/power/initialize_battery.cpp rename to src/components/real/power/initialize_battery.cpp diff --git a/src/components/power/initialize_battery.hpp b/src/components/real/power/initialize_battery.hpp similarity index 65% rename from src/components/power/initialize_battery.hpp rename to src/components/real/power/initialize_battery.hpp index 2e80452d4..d960be9a9 100644 --- a/src/components/power/initialize_battery.hpp +++ b/src/components/real/power/initialize_battery.hpp @@ -3,10 +3,10 @@ * @brief Initialize function of BAT */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ -#define S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ +#define S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ -#include +#include /* * @fn InitBAT @@ -18,4 +18,4 @@ */ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_BATTERY_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp similarity index 100% rename from src/components/power/initialize_pcu_initial_study.cpp rename to src/components/real/power/initialize_pcu_initial_study.cpp diff --git a/src/components/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp similarity index 71% rename from src/components/power/initialize_pcu_initial_study.hpp rename to src/components/real/power/initialize_pcu_initial_study.hpp index 631e2ece4..1dc2f9a79 100644 --- a/src/components/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -3,10 +3,10 @@ * @brief Initialize function of PCU_InitialStudy */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ -#define S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ +#define S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ -#include +#include /* * @fn InitPCU_InitialStudy @@ -21,4 +21,4 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp similarity index 100% rename from src/components/power/initialize_solar_array_panel.cpp rename to src/components/real/power/initialize_solar_array_panel.cpp diff --git a/src/components/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp similarity index 80% rename from src/components/power/initialize_solar_array_panel.hpp rename to src/components/real/power/initialize_solar_array_panel.hpp index 2a9280059..878b3a25a 100644 --- a/src/components/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -3,10 +3,10 @@ * @brief Initialize function of SAP (Solar Array Panel) */ -#ifndef S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ -#define S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ +#define S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ -#include +#include /* * @fn InitSAP @@ -32,4 +32,4 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons */ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time); -#endif // S2E_COMPONENTS_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp similarity index 98% rename from src/components/power/pcu_initial_study.cpp rename to src/components/real/power/pcu_initial_study.cpp index fc4d4fa91..fe0967015 100644 --- a/src/components/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -6,7 +6,7 @@ #include "pcu_initial_study.hpp" #include -#include +#include #include PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time) diff --git a/src/components/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp similarity index 91% rename from src/components/power/pcu_initial_study.hpp rename to src/components/real/power/pcu_initial_study.hpp index 89e7e7d15..d88461a96 100644 --- a/src/components/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -3,13 +3,13 @@ * @brief Component emulation of Power Control Unit for initial study of spacecraft project */ -#ifndef S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ -#define S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_PCU_INITIAL_STUDY_HPP_ +#define S2E_COMPONENTS_REAL_POWER_PCU_INITIAL_STUDY_HPP_ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" #include "battery.hpp" #include "solar_array_panel.hpp" @@ -81,4 +81,4 @@ class PCU_InitialStudy : public ComponentBase, public ILoggable { void UpdateChargeCurrentAndBusVoltage(); }; -#endif // S2E_COMPONENTS_POWER_PCU_INITIAL_STUDY_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp similarity index 100% rename from src/components/power/power_control_unit.cpp rename to src/components/real/power/power_control_unit.cpp diff --git a/src/components/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp similarity index 92% rename from src/components/power/power_control_unit.hpp rename to src/components/real/power/power_control_unit.hpp index 17b0edb86..9ae65ec96 100644 --- a/src/components/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -3,14 +3,14 @@ * @brief Component emulation of Power Control Unit */ -#ifndef S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ -#define S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_POWER_CONTROL_UNIT_HPP_ +#define S2E_COMPONENTS_REAL_POWER_POWER_CONTROL_UNIT_HPP_ #include #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" /* * @class PCU @@ -94,4 +94,4 @@ class PCU : public ComponentBase, public ILoggable { std::map ports_; //!< Power port list }; -#endif // S2E_COMPONENTS_POWER_POWER_CONTROL_UNIT_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_POWER_CONTROL_UNIT_HPP_ diff --git a/src/components/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp similarity index 98% rename from src/components/power/solar_array_panel.cpp rename to src/components/real/power/solar_array_panel.cpp index 5d23115ea..ec61cc424 100644 --- a/src/components/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -5,7 +5,7 @@ #include "solar_array_panel.hpp" -#include +#include #include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, diff --git a/src/components/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp similarity index 96% rename from src/components/power/solar_array_panel.hpp rename to src/components/real/power/solar_array_panel.hpp index 93f72ea2d..3414322bd 100644 --- a/src/components/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -3,15 +3,15 @@ * @brief Component emulation of Solar Array Panel */ -#ifndef S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ -#define S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ +#ifndef S2E_COMPONENTS_REAL_POWER_SOLAR_ARRAY_PANEL_HPP_ +#define S2E_COMPONENTS_REAL_POWER_SOLAR_ARRAY_PANEL_HPP_ #include #include #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" class SAP : public ComponentBase, public ILoggable { public: @@ -129,4 +129,4 @@ class SAP : public ComponentBase, public ILoggable { void MainRoutine(int time_count) override; }; -#endif // S2E_COMPONENTS_POWER_SOLAR_ARRAY_PANEL_HPP_ +#endif // S2E_COMPONENTS_REAL_POWER_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 09da69085..19942119d 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include #include #include #include From fef23c0983a18c1db3404c06b668ed9029527e98 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:44:59 +0100 Subject: [PATCH 0482/1086] Move aocs --- src/components/CMakeLists.txt | 32 +++++++++---------- .../{ => real}/aocs/gnss_receiver.cpp | 0 .../{ => real}/aocs/gnss_receiver.hpp | 8 ++--- .../{ => real}/aocs/gyro_sensor.cpp | 0 .../{ => real}/aocs/gyro_sensor.hpp | 10 +++--- .../aocs/initialize_gnss_receiver.cpp | 0 .../aocs/initialize_gnss_receiver.hpp | 8 ++--- .../aocs/initialize_gyro_sensor.cpp | 2 +- .../aocs/initialize_gyro_sensor.hpp | 8 ++--- .../aocs/initialize_magnetometer.cpp | 2 +- .../aocs/initialize_magnetometer.hpp | 8 ++--- .../aocs/initialize_magnetorquer.cpp | 0 .../aocs/initialize_magnetorquer.hpp | 8 ++--- .../aocs/initialize_reaction_wheel.cpp | 0 .../aocs/initialize_reaction_wheel.hpp | 8 ++--- .../aocs/initialize_star_sensor.cpp | 0 .../aocs/initialize_star_sensor.hpp | 8 ++--- .../{ => real}/aocs/initialize_sun_sensor.cpp | 0 .../{ => real}/aocs/initialize_sun_sensor.hpp | 8 ++--- .../{ => real}/aocs/magnetometer.cpp | 0 .../{ => real}/aocs/magnetometer.hpp | 10 +++--- .../{ => real}/aocs/magnetorquer.cpp | 0 .../{ => real}/aocs/magnetorquer.hpp | 8 ++--- .../{ => real}/aocs/reaction_wheel.cpp | 0 .../{ => real}/aocs/reaction_wheel.hpp | 8 ++--- .../{ => real}/aocs/reaction_wheel_jitter.cpp | 0 .../{ => real}/aocs/reaction_wheel_jitter.hpp | 6 ++-- .../{ => real}/aocs/reaction_wheel_ode.cpp | 0 .../{ => real}/aocs/reaction_wheel_ode.hpp | 6 ++-- .../{ => real}/aocs/star_sensor.cpp | 0 .../{ => real}/aocs/star_sensor.hpp | 8 ++--- src/components/{ => real}/aocs/sun_sensor.cpp | 0 src/components/{ => real}/aocs/sun_sensor.hpp | 8 ++--- .../sample_spacecraft/sample_components.hpp | 14 ++++---- 34 files changed, 89 insertions(+), 89 deletions(-) rename src/components/{ => real}/aocs/gnss_receiver.cpp (100%) rename src/components/{ => real}/aocs/gnss_receiver.hpp (98%) rename src/components/{ => real}/aocs/gyro_sensor.cpp (100%) rename src/components/{ => real}/aocs/gyro_sensor.hpp (92%) rename src/components/{ => real}/aocs/initialize_gnss_receiver.cpp (100%) rename src/components/{ => real}/aocs/initialize_gnss_receiver.hpp (84%) rename src/components/{ => real}/aocs/initialize_gyro_sensor.cpp (97%) rename src/components/{ => real}/aocs/initialize_gyro_sensor.hpp (82%) rename src/components/{ => real}/aocs/initialize_magnetometer.cpp (97%) rename src/components/{ => real}/aocs/initialize_magnetometer.hpp (82%) rename src/components/{ => real}/aocs/initialize_magnetorquer.cpp (100%) rename src/components/{ => real}/aocs/initialize_magnetorquer.hpp (82%) rename src/components/{ => real}/aocs/initialize_reaction_wheel.cpp (100%) rename src/components/{ => real}/aocs/initialize_reaction_wheel.hpp (82%) rename src/components/{ => real}/aocs/initialize_star_sensor.cpp (100%) rename src/components/{ => real}/aocs/initialize_star_sensor.hpp (84%) rename src/components/{ => real}/aocs/initialize_sun_sensor.cpp (100%) rename src/components/{ => real}/aocs/initialize_sun_sensor.hpp (84%) rename src/components/{ => real}/aocs/magnetometer.cpp (100%) rename src/components/{ => real}/aocs/magnetometer.hpp (92%) rename src/components/{ => real}/aocs/magnetorquer.cpp (100%) rename src/components/{ => real}/aocs/magnetorquer.hpp (97%) rename src/components/{ => real}/aocs/reaction_wheel.cpp (100%) rename src/components/{ => real}/aocs/reaction_wheel.hpp (98%) rename src/components/{ => real}/aocs/reaction_wheel_jitter.cpp (100%) rename src/components/{ => real}/aocs/reaction_wheel_jitter.hpp (96%) rename src/components/{ => real}/aocs/reaction_wheel_ode.cpp (100%) rename src/components/{ => real}/aocs/reaction_wheel_ode.hpp (92%) rename src/components/{ => real}/aocs/star_sensor.cpp (100%) rename src/components/{ => real}/aocs/star_sensor.hpp (97%) rename src/components/{ => real}/aocs/sun_sensor.cpp (100%) rename src/components/{ => real}/aocs/sun_sensor.hpp (97%) diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 02aec3749..8182f10a2 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -8,22 +8,22 @@ base/i2c_controller.cpp base/i2c_target_communication_with_obc.cpp base/gpio_connection_with_obc.cpp -aocs/gyro_sensor.cpp -aocs/initialize_gyro_sensor.cpp -aocs/magnetometer.cpp -aocs/initialize_magnetometer.cpp -aocs/magnetorquer.cpp -aocs/initialize_magnetorquer.cpp -aocs/reaction_wheel_ode.cpp -aocs/reaction_wheel.cpp -aocs/initialize_reaction_wheel.cpp -aocs/reaction_wheel_jitter.cpp -aocs/star_sensor.cpp -aocs/initialize_star_sensor.cpp -aocs/sun_sensor.cpp -aocs/initialize_sun_sensor.cpp -aocs/gnss_receiver.cpp -aocs/initialize_gnss_receiver.cpp +real/aocs/gyro_sensor.cpp +real/aocs/initialize_gyro_sensor.cpp +real/aocs/magnetometer.cpp +real/aocs/initialize_magnetometer.cpp +real/aocs/magnetorquer.cpp +real/aocs/initialize_magnetorquer.cpp +real/aocs/reaction_wheel_ode.cpp +real/aocs/reaction_wheel.cpp +real/aocs/initialize_reaction_wheel.cpp +real/aocs/reaction_wheel_jitter.cpp +real/aocs/star_sensor.cpp +real/aocs/initialize_star_sensor.cpp +real/aocs/sun_sensor.cpp +real/aocs/initialize_sun_sensor.cpp +real/aocs/gnss_receiver.cpp +real/aocs/initialize_gnss_receiver.cpp real/cdh/on_board_computer.cpp real/cdh/on_board_computer_with_c2a.cpp diff --git a/src/components/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp similarity index 100% rename from src/components/aocs/gnss_receiver.cpp rename to src/components/real/aocs/gnss_receiver.cpp diff --git a/src/components/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp similarity index 98% rename from src/components/aocs/gnss_receiver.hpp rename to src/components/real/aocs/gnss_receiver.hpp index 860950c91..688932b50 100644 --- a/src/components/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate GNSS receiver */ -#ifndef S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ -#define S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_GNSS_RECEIVER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_GNSS_RECEIVER_HPP_ #include #include @@ -13,7 +13,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" using libra::Vector; @@ -214,4 +214,4 @@ class GNSSReceiver : public ComponentBase, public ILoggable { void ConvertJulianDayToGPSTime(const double JulianDay); }; -#endif // S2E_COMPONENTS_AOCS_GNSS_RECEIVER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_GNSS_RECEIVER_HPP_ diff --git a/src/components/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp similarity index 100% rename from src/components/aocs/gyro_sensor.cpp rename to src/components/real/aocs/gyro_sensor.cpp diff --git a/src/components/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp similarity index 92% rename from src/components/aocs/gyro_sensor.hpp rename to src/components/real/aocs/gyro_sensor.hpp index 48392abcc..e525e602d 100644 --- a/src/components/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -3,15 +3,15 @@ * @brief Class to emulate gyro sensor (angular velocity sensor) */ -#ifndef S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_GYRO_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_GYRO_SENSOR_HPP_ #include #include #include -#include "../base/component.hpp" -#include "../base/sensor.hpp" +#include "../../base/component.hpp" +#include "../../base/sensor.hpp" const size_t kGyroDim = 3; //!< Dimension of gyro sensor @@ -85,4 +85,4 @@ class Gyro : public ComponentBase, public SensorBase, public ILoggable const Dynamics* dynamics_; //!< Dynamics information }; -#endif // S2E_COMPONENTS_AOCS_GYRO_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_GYRO_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp similarity index 100% rename from src/components/aocs/initialize_gnss_receiver.cpp rename to src/components/real/aocs/initialize_gnss_receiver.cpp diff --git a/src/components/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp similarity index 84% rename from src/components/aocs/initialize_gnss_receiver.hpp rename to src/components/real/aocs/initialize_gnss_receiver.hpp index 908b044dd..0a13347ef 100644 --- a/src/components/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for GNSS Receiver */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ -#include +#include /** * @fn InitGNSSReceiver @@ -34,4 +34,4 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp similarity index 97% rename from src/components/aocs/initialize_gyro_sensor.cpp rename to src/components/real/aocs/initialize_gyro_sensor.cpp index 10672f0fc..9c5eb1025 100644 --- a/src/components/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -6,7 +6,7 @@ #include -#include "../base/initialize_sensor.hpp" +#include "../../base/initialize_sensor.hpp" Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); diff --git a/src/components/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp similarity index 82% rename from src/components/aocs/initialize_gyro_sensor.hpp rename to src/components/real/aocs/initialize_gyro_sensor.hpp index bec1b016f..5ac689cbb 100644 --- a/src/components/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for gyro sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ -#include +#include /** * @fn InitGyro @@ -31,4 +31,4 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp similarity index 97% rename from src/components/aocs/initialize_magnetometer.cpp rename to src/components/real/aocs/initialize_magnetometer.cpp index 7a70dcf89..f31fe38a1 100644 --- a/src/components/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -4,7 +4,7 @@ */ #include "initialize_magnetometer.hpp" -#include "../base/initialize_sensor.hpp" +#include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { diff --git a/src/components/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp similarity index 82% rename from src/components/aocs/initialize_magnetometer.hpp rename to src/components/real/aocs/initialize_magnetometer.hpp index 196e3547b..2c6953855 100644 --- a/src/components/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for magnetometer */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ -#include +#include /** * @fn InitMagSensor @@ -31,4 +31,4 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETOMETER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp similarity index 100% rename from src/components/aocs/initialize_magnetorquer.cpp rename to src/components/real/aocs/initialize_magnetorquer.cpp diff --git a/src/components/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp similarity index 82% rename from src/components/aocs/initialize_magnetorquer.hpp rename to src/components/real/aocs/initialize_magnetorquer.hpp index e3e7e3111..548463f55 100644 --- a/src/components/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for magnetorquer */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ -#include +#include /** * @fn InitMagTorquer @@ -31,4 +31,4 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_MAGNETORQUER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp similarity index 100% rename from src/components/aocs/initialize_reaction_wheel.cpp rename to src/components/real/aocs/initialize_reaction_wheel.cpp diff --git a/src/components/aocs/initialize_reaction_wheel.hpp b/src/components/real/aocs/initialize_reaction_wheel.hpp similarity index 82% rename from src/components/aocs/initialize_reaction_wheel.hpp rename to src/components/real/aocs/initialize_reaction_wheel.hpp index 5cd94d3a6..f4f035d02 100644 --- a/src/components/aocs/initialize_reaction_wheel.hpp +++ b/src/components/real/aocs/initialize_reaction_wheel.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for Reaction Wheel */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ -#include +#include /** * @fn InitRWModel @@ -31,4 +31,4 @@ RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, double compo_update_step); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ diff --git a/src/components/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp similarity index 100% rename from src/components/aocs/initialize_star_sensor.cpp rename to src/components/real/aocs/initialize_star_sensor.cpp diff --git a/src/components/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp similarity index 84% rename from src/components/aocs/initialize_star_sensor.hpp rename to src/components/real/aocs/initialize_star_sensor.hpp index 59325efc4..18e1b99cd 100644 --- a/src/components/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for star sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ -#include +#include /** * @fn InitSTT @@ -34,4 +34,4 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const std::string fname, d STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_STAR_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp similarity index 100% rename from src/components/aocs/initialize_sun_sensor.cpp rename to src/components/real/aocs/initialize_sun_sensor.cpp diff --git a/src/components/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp similarity index 84% rename from src/components/aocs/initialize_sun_sensor.hpp rename to src/components/real/aocs/initialize_sun_sensor.hpp index 4eba4b5f1..b67f9a119 100644 --- a/src/components/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -3,10 +3,10 @@ * @brief Initialize functions for sun sensor */ -#ifndef S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ -#include +#include /** * @fn InitSunSensor @@ -32,4 +32,4 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::str SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info); -#endif // S2E_COMPONENTS_AOCS_INITIALIZE_SUN_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp similarity index 100% rename from src/components/aocs/magnetometer.cpp rename to src/components/real/aocs/magnetometer.cpp diff --git a/src/components/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp similarity index 92% rename from src/components/aocs/magnetometer.hpp rename to src/components/real/aocs/magnetometer.hpp index 75419b9fa..d5bdcb080 100644 --- a/src/components/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -3,15 +3,15 @@ * @brief Class to emulate magnetometer */ -#ifndef S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ -#define S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_MAGNETOMETER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_MAGNETOMETER_HPP_ #include #include #include -#include "../base/component.hpp" -#include "../base/sensor.hpp" +#include "../../base/component.hpp" +#include "../../base/sensor.hpp" const size_t kMagDim = 3; //!< Dimension of magnetometer @@ -85,4 +85,4 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg const MagEnvironment* magnet_; //!< Geomagnetic environment }; -#endif // S2E_COMPONENTS_AOCS_MAGNETOMETER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_MAGNETOMETER_HPP_ diff --git a/src/components/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp similarity index 100% rename from src/components/aocs/magnetorquer.cpp rename to src/components/real/aocs/magnetorquer.cpp diff --git a/src/components/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp similarity index 97% rename from src/components/aocs/magnetorquer.hpp rename to src/components/real/aocs/magnetorquer.hpp index c87ab2b54..cde36655a 100644 --- a/src/components/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate magnetorquer */ -#ifndef S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ -#define S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_MAGNETORQUER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_MAGNETORQUER_HPP_ #include #include @@ -14,7 +14,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" const size_t kMtqDim = 3; //!< Dimension of magnetorquer @@ -134,4 +134,4 @@ class MagTorquer : public ComponentBase, public ILoggable { libra::Vector CalcOutputTorque(void); }; -#endif // S2E_COMPONENTS_AOCS_MAGNETORQUER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_MAGNETORQUER_HPP_ diff --git a/src/components/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp similarity index 100% rename from src/components/aocs/reaction_wheel.cpp rename to src/components/real/aocs/reaction_wheel.cpp diff --git a/src/components/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp similarity index 98% rename from src/components/aocs/reaction_wheel.hpp rename to src/components/real/aocs/reaction_wheel.hpp index ac36c2214..96ff42604 100644 --- a/src/components/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate Reaction Wheel */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_HPP_ #include #include @@ -13,7 +13,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" #include "reaction_wheel_jitter.hpp" #include "reaction_wheel_ode.hpp" @@ -235,4 +235,4 @@ class RWModel : public ComponentBase, public ILoggable { void Initialize(); }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_HPP_ diff --git a/src/components/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp similarity index 100% rename from src/components/aocs/reaction_wheel_jitter.cpp rename to src/components/real/aocs/reaction_wheel_jitter.cpp diff --git a/src/components/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp similarity index 96% rename from src/components/aocs/reaction_wheel_jitter.hpp rename to src/components/real/aocs/reaction_wheel_jitter.hpp index c904f6d0a..9b6694c6c 100644 --- a/src/components/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -3,8 +3,8 @@ * @brief Class to calculate RW high-frequency jitter effect */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_JITTER_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_JITTER_HPP_ #pragma once #include @@ -122,4 +122,4 @@ class RWJitter { void CalcCoef(); }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_JITTER_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_JITTER_HPP_ diff --git a/src/components/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp similarity index 100% rename from src/components/aocs/reaction_wheel_ode.cpp rename to src/components/real/aocs/reaction_wheel_ode.cpp diff --git a/src/components/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp similarity index 92% rename from src/components/aocs/reaction_wheel_ode.hpp rename to src/components/real/aocs/reaction_wheel_ode.hpp index db4c74e1d..510a794b8 100644 --- a/src/components/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -3,8 +3,8 @@ * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -#ifndef S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ -#define S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_ODE_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_ODE_HPP_ #include #include @@ -70,4 +70,4 @@ class RwOde : public libra::ODE<1> { double target_angular_velocity_; //!< Target angular velocity [rad/s] }; -#endif // S2E_COMPONENTS_AOCS_REACTION_WHEEL_ODE_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_ODE_HPP_ diff --git a/src/components/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp similarity index 100% rename from src/components/aocs/star_sensor.cpp rename to src/components/real/aocs/star_sensor.cpp diff --git a/src/components/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp similarity index 97% rename from src/components/aocs/star_sensor.hpp rename to src/components/real/aocs/star_sensor.hpp index 7f1b324d6..13fb155fb 100644 --- a/src/components/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate star tracker */ -#ifndef S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_STAR_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_STAR_SENSOR_HPP_ #include #include @@ -15,7 +15,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" #include "dynamics/dynamics.hpp" /* @@ -203,4 +203,4 @@ class STT : public ComponentBase, public ILoggable { void Initialize(); }; -#endif // S2E_COMPONENTS_AOCS_STAR_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_STAR_SENSOR_HPP_ diff --git a/src/components/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp similarity index 100% rename from src/components/aocs/sun_sensor.cpp rename to src/components/real/aocs/sun_sensor.cpp diff --git a/src/components/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp similarity index 97% rename from src/components/aocs/sun_sensor.hpp rename to src/components/real/aocs/sun_sensor.hpp index 6050face7..77a6fd9be 100644 --- a/src/components/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -3,8 +3,8 @@ * @brief Class to emulate sun sensor */ -#ifndef S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ -#define S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_AOCS_SUN_SENSOR_HPP_ +#define S2E_COMPONENTS_REAL_AOCS_SUN_SENSOR_HPP_ #include #include @@ -13,7 +13,7 @@ #include #include -#include "../base/component.hpp" +#include "../../base/component.hpp" /* * @class SunSensor @@ -139,4 +139,4 @@ class SunSensor : public ComponentBase, public ILoggable { void CalcSolarIlluminance(); }; -#endif // S2E_COMPONENTS_AOCS_SUN_SENSOR_HPP_ +#endif // S2E_COMPONENTS_REAL_AOCS_SUN_SENSOR_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 19942119d..1ae1b46f2 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,13 +6,13 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include #include #include #include From e8f62dd55ee638217378866be6577a6cb93e0802 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 15:53:45 +0100 Subject: [PATCH 0483/1086] Move communication --- src/components/CMakeLists.txt | 10 +++++----- .../initialize_ground_station_calculator.hpp | 19 ------------------- .../{ => real}/communication/antenna.cpp | 0 .../{ => real}/communication/antenna.hpp | 6 +++--- .../antenna_radiation_pattern.cpp | 0 .../antenna_radiation_pattern.hpp | 6 +++--- .../ground_station_calculator.cpp | 0 .../ground_station_calculator.hpp | 8 ++++---- .../communication/initialize_antenna.cpp | 0 .../communication/initialize_antenna.hpp | 8 ++++---- .../initialize_ground_station_calculator.cpp | 0 .../initialize_ground_station_calculator.hpp | 19 +++++++++++++++++++ .../sample_ground_station.hpp | 4 ++-- .../sample_ground_station_components.hpp | 4 ++-- .../sample_spacecraft/sample_components.hpp | 2 +- 15 files changed, 43 insertions(+), 43 deletions(-) delete mode 100644 src/components/communication/initialize_ground_station_calculator.hpp rename src/components/{ => real}/communication/antenna.cpp (100%) rename src/components/{ => real}/communication/antenna.hpp (96%) rename src/components/{ => real}/communication/antenna_radiation_pattern.cpp (100%) rename src/components/{ => real}/communication/antenna_radiation_pattern.hpp (90%) rename src/components/{ => real}/communication/ground_station_calculator.cpp (100%) rename src/components/{ => real}/communication/ground_station_calculator.hpp (95%) rename src/components/{ => real}/communication/initialize_antenna.cpp (100%) rename src/components/{ => real}/communication/initialize_antenna.hpp (55%) rename src/components/{ => real}/communication/initialize_ground_station_calculator.cpp (100%) create mode 100644 src/components/real/communication/initialize_ground_station_calculator.hpp diff --git a/src/components/CMakeLists.txt b/src/components/CMakeLists.txt index 8182f10a2..b8963906a 100644 --- a/src/components/CMakeLists.txt +++ b/src/components/CMakeLists.txt @@ -28,11 +28,11 @@ real/aocs/initialize_gnss_receiver.cpp real/cdh/on_board_computer.cpp real/cdh/on_board_computer_with_c2a.cpp -communication/antenna.cpp -communication/antenna_radiation_pattern.cpp -communication/initialize_antenna.cpp -communication/ground_station_calculator.cpp -communication/initialize_ground_station_calculator.cpp +real/communication/antenna.cpp +real/communication/antenna_radiation_pattern.cpp +real/communication/initialize_antenna.cpp +real/communication/ground_station_calculator.cpp +real/communication/initialize_ground_station_calculator.cpp examples/example_change_structure.cpp examples/example_serial_communication_with_obc.cpp diff --git a/src/components/communication/initialize_ground_station_calculator.hpp b/src/components/communication/initialize_ground_station_calculator.hpp deleted file mode 100644 index 7c17b689a..000000000 --- a/src/components/communication/initialize_ground_station_calculator.hpp +++ /dev/null @@ -1,19 +0,0 @@ -/* - * @file initialize_ground_station_calculator.hpp.hpp - * @brief Initialize function for Ground Station Calculator - */ - -#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ -#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ - -#include - -/* - * @fn InitGscalculator - * @brief Initialize function for Ground Station Calculator - * @param [in] fname: Path to initialize file - */ - -GScalculator InitGScalculator(const std::string fname); - -#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/communication/antenna.cpp b/src/components/real/communication/antenna.cpp similarity index 100% rename from src/components/communication/antenna.cpp rename to src/components/real/communication/antenna.cpp diff --git a/src/components/communication/antenna.hpp b/src/components/real/communication/antenna.hpp similarity index 96% rename from src/components/communication/antenna.hpp rename to src/components/real/communication/antenna.hpp index 7cd039fa9..753bb662f 100644 --- a/src/components/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -3,8 +3,8 @@ * @brief Component emulation: RF antenna */ -#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ -#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ +#ifndef S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_HPP_ +#define S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_HPP_ #include #include @@ -150,4 +150,4 @@ class Antenna { AntennaGainModel SetAntennaGainModel(const std::string gain_model_name); -#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_HPP_ +#endif // S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_HPP_ diff --git a/src/components/communication/antenna_radiation_pattern.cpp b/src/components/real/communication/antenna_radiation_pattern.cpp similarity index 100% rename from src/components/communication/antenna_radiation_pattern.cpp rename to src/components/real/communication/antenna_radiation_pattern.cpp diff --git a/src/components/communication/antenna_radiation_pattern.hpp b/src/components/real/communication/antenna_radiation_pattern.hpp similarity index 90% rename from src/components/communication/antenna_radiation_pattern.hpp rename to src/components/real/communication/antenna_radiation_pattern.hpp index 02149054a..35490c6b1 100644 --- a/src/components/communication/antenna_radiation_pattern.hpp +++ b/src/components/real/communication/antenna_radiation_pattern.hpp @@ -3,8 +3,8 @@ * @brief Class to manage antenna radiation pattern */ -#ifndef S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ -#define S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ +#ifndef S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ +#define S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ #include #include @@ -62,4 +62,4 @@ class AntennaRadiationPattern { std::vector> gain_dBi_; //!< Antenna gain table [dBi] }; -#endif // S2E_COMPONENTS_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ +#endif // S2E_COMPONENTS_REAL_COMMUNICATION_ANTENNA_RADIATION_PATTERN_HPP_ diff --git a/src/components/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp similarity index 100% rename from src/components/communication/ground_station_calculator.cpp rename to src/components/real/communication/ground_station_calculator.cpp diff --git a/src/components/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp similarity index 95% rename from src/components/communication/ground_station_calculator.hpp rename to src/components/real/communication/ground_station_calculator.hpp index 94e52f619..df3bc8f28 100644 --- a/src/components/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -4,10 +4,10 @@ * @note TODO: This class is not `Component`. We need to move this to `Analysis` category and use this as library in future. */ -#ifndef S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ -#define S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ +#ifndef S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ +#define S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ -#include +#include #include #include #include @@ -138,4 +138,4 @@ class GScalculator : public ILoggable { double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); }; -#endif // S2E_COMPONENTS_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ +#endif // S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/communication/initialize_antenna.cpp b/src/components/real/communication/initialize_antenna.cpp similarity index 100% rename from src/components/communication/initialize_antenna.cpp rename to src/components/real/communication/initialize_antenna.cpp diff --git a/src/components/communication/initialize_antenna.hpp b/src/components/real/communication/initialize_antenna.hpp similarity index 55% rename from src/components/communication/initialize_antenna.hpp rename to src/components/real/communication/initialize_antenna.hpp index c21a7bb1d..8d6f1c906 100644 --- a/src/components/communication/initialize_antenna.hpp +++ b/src/components/real/communication/initialize_antenna.hpp @@ -3,10 +3,10 @@ * @brief Initialize function for Antenna */ -#ifndef S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ -#define S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ +#ifndef S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ +#define S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ -#include +#include /* * @fn InitAntenna @@ -16,4 +16,4 @@ */ Antenna InitAntenna(const int antenna_id, const std::string file_name); -#endif // S2E_COMPONENTS_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ +#endif // S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_ANTENNA_HPP_ diff --git a/src/components/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp similarity index 100% rename from src/components/communication/initialize_ground_station_calculator.cpp rename to src/components/real/communication/initialize_ground_station_calculator.cpp diff --git a/src/components/real/communication/initialize_ground_station_calculator.hpp b/src/components/real/communication/initialize_ground_station_calculator.hpp new file mode 100644 index 000000000..776a73280 --- /dev/null +++ b/src/components/real/communication/initialize_ground_station_calculator.hpp @@ -0,0 +1,19 @@ +/* + * @file initialize_ground_station_calculator.hpp.hpp + * @brief Initialize function for Ground Station Calculator + */ + +#ifndef S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ +#define S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ + +#include + +/* + * @fn InitGscalculator + * @brief Initialize function for Ground Station Calculator + * @param [in] fname: Path to initialize file + */ + +GScalculator InitGScalculator(const std::string fname); + +#endif // S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index d4cabce48..41a04a193 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ -#include -#include +#include +#include #include #include diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 529a59421..14c97fe12 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -6,8 +6,8 @@ #ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ #define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ -#include -#include +#include +#include /** * @class SampleGSComponents diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 1ae1b46f2..9ec18c1f4 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -14,7 +14,7 @@ #include #include #include -#include +#include #include #include #include From e6edc77d70b122b34830866dd4904cb0bb804169 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Feb 2023 16:58:07 +0100 Subject: [PATCH 0484/1086] Fix format --- .../sample_spacecraft/sample_components.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 9ec18c1f4..8aefc19f9 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -6,6 +6,12 @@ #ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ #define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ +#include +#include +#include +#include +#include +#include #include #include #include @@ -15,12 +21,6 @@ #include #include #include -#include -#include -#include -#include -#include -#include #include #include #include From 2d9d3dfcfcc1e4a4d806859910c6533e2bda6b36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 08:57:02 +0100 Subject: [PATCH 0485/1086] Remove using --- .../global/celestial_information.cpp | 48 +++++++++---------- .../global/celestial_information.hpp | 15 +++--- 2 files changed, 29 insertions(+), 34 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index f9225634f..137b7f77d 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -14,9 +14,7 @@ #include #include -using namespace std; - -CelestialInformation::CelestialInformation(string inertial_frame, string aber_cor, string center_obj, RotationMode rotation_mode, +CelestialInformation::CelestialInformation(std::string inertial_frame, std::string aber_cor, std::string center_obj, RotationMode rotation_mode, int num_of_selected_body, int* selected_body) : num_of_selected_body_(num_of_selected_body), selected_body_(selected_body), @@ -102,7 +100,7 @@ CelestialInformation::~CelestialInformation() { void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { // Convert time SpiceDouble et; - string jd = "jd " + to_string(current_jd); + std::string jd = "jd " + std::to_string(current_jd); str2et_c(jd.c_str(), &et); for (int i = 0; i < num_of_selected_body_; i++) { @@ -129,26 +127,26 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { } // Getters -Vector<3> CelestialInformation::GetPosFromCenter_i(const int id) const { - Vector<3> pos(0.0); +libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const int id) const { + libra::Vector<3> pos(0.0); if (id > num_of_selected_body_) return pos; for (int i = 0; i < 3; i++) pos[i] = celes_objects_pos_from_center_i_[id * 3 + i]; return pos; } -Vector<3> CelestialInformation::GetVelFromCenter_i(const int id) const { - Vector<3> vel(0.0); +libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const int id) const { + libra::Vector<3> vel(0.0); if (id > num_of_selected_body_) return vel; for (int i = 0; i < 3; i++) vel[i] = celes_objects_vel_from_center_i_[id * 3 + i]; return vel; } -Vector<3> CelestialInformation::GetPosFromCenter_i(const char* body_name) const { +libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const char* body_name) const { int id = CalcBodyIdFromName(body_name); return GetPosFromCenter_i(id); } -Vector<3> CelestialInformation::GetVelFromCenter_i(const char* body_name) const { +libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const char* body_name) const { int id = CalcBodyIdFromName(body_name); return GetVelFromCenter_i(id); } @@ -160,14 +158,14 @@ double CelestialInformation::GetGravityConstant(const char* body_name) const { double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_obj_.c_str()); } -Vector<3> CelestialInformation::GetRadii(const int id) const { - Vector<3> radii(0.0); +libra::Vector<3> CelestialInformation::GetRadii(const int id) const { + libra::Vector<3> radii(0.0); if (id > num_of_selected_body_) return radii; for (int i = 0; i < 3; i++) radii[i] = celes_objects_planetographic_radii_m_[id * 3 + i]; return radii; } -Vector<3> CelestialInformation::GetRadiiFromName(const char* body_name) const { +libra::Vector<3> CelestialInformation::GetRadiiFromName(const char* body_name) const { int id = CalcBodyIdFromName(body_name); return GetRadii(id); } @@ -193,19 +191,19 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { return index; } -string CelestialInformation::GetLogHeader() const { +std::string CelestialInformation::GetLogHeader() const { SpiceBoolean found; const int maxlen = 100; char namebuf[maxlen]; - string str_tmp = ""; + std::string str_tmp = ""; for (int i = 0; i < num_of_selected_body_; i++) { SpiceInt planet_id = selected_body_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); - string name = namebuf; + std::string name = namebuf; std::transform(name.begin(), name.end(), name.begin(), ::tolower); - string body_pos = name + "_position"; - string body_vel = name + "_velocity"; + std::string body_pos = name + "_position"; + std::string body_vel = name + "_velocity"; str_tmp += WriteVector(body_pos, "i", "m", 3); str_tmp += WriteVector(body_vel, "i", "m/s", 3); @@ -213,8 +211,8 @@ string CelestialInformation::GetLogHeader() const { return str_tmp; } -string CelestialInformation::GetLogValue() const { - string str_tmp = ""; +std::string CelestialInformation::GetLogValue() const { + std::string str_tmp = ""; for (int i = 0; i < num_of_selected_body_; i++) { for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celes_objects_pos_from_center_i_[i * 3 + j]); @@ -230,21 +228,21 @@ void CelestialInformation::DebugOutput(void) { SpiceBoolean found; const int maxlen = 100; char namebuf[maxlen]; - cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " - "VELx,y,z[m/s] from SC"; + std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " + "VELx,y,z[m/s] from SC"; for (int i = 0; i < num_of_selected_body_; i++) { SpiceInt planet_id = selected_body_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); // cout< GetPosFromCenter_i(const int id) const; + libra::Vector<3> GetPosFromCenter_i(const int id) const; /** * @fn GetPosFromCenter_i * @brief Return position from the center body in the inertial frame [m] * @param [in] body_name: Name of the body defined in the SPICE */ - Vector<3> GetPosFromCenter_i(const char* body_name) const; + libra::Vector<3> GetPosFromCenter_i(const char* body_name) const; /** * @fn GetVelFromCenter_i * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] id: ID of CelestialInformation list */ - Vector<3> GetVelFromCenter_i(const int id) const; + libra::Vector<3> GetVelFromCenter_i(const int id) const; /** * @fn GetVelFromCenter_i * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] body_name: Name of the body defined in the SPICE */ - Vector<3> GetVelFromCenter_i(const char* body_name) const; + libra::Vector<3> GetVelFromCenter_i(const char* body_name) const; // Gravity constants /** @@ -114,13 +111,13 @@ class CelestialInformation : public ILoggable { * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - Vector<3> GetRadii(const int id) const; + libra::Vector<3> GetRadii(const int id) const; /** * @fn GetRadiiFromName * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] body_name: Name of the body defined in the SPICE */ - Vector<3> GetRadiiFromName(const char* body_name) const; + libra::Vector<3> GetRadiiFromName(const char* body_name) const; /** * @fn GetMeanRadiusFromName * @brief Return mean radius of a celestial body [m] From 1ae2a2c814dadf87e8450ba9af4b6cb2417f282a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 08:58:31 +0100 Subject: [PATCH 0486/1086] Remove unnecessary include files --- src/environment/global/celestial_information.cpp | 3 ++- src/environment/global/celestial_information.hpp | 6 ------ 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 137b7f77d..37da06b8d 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -11,9 +11,10 @@ #include #include -#include #include +#include "library/logger/log_utility.hpp" + CelestialInformation::CelestialInformation(std::string inertial_frame, std::string aber_cor, std::string center_obj, RotationMode rotation_mode, int num_of_selected_body, int* selected_body) : num_of_selected_body_(num_of_selected_body), diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 4f8d7451e..454b5c493 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -7,14 +7,8 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ -#include -#include - #include "celestial_rotation.hpp" #include "library/logger/loggable.hpp" -#include "library/math/matrix.hpp" -#include "library/math/matrix_vector.hpp" -#include "library/math/quaternion.hpp" #include "library/math/vector.hpp" /** From a09d080898cb3c5afe448b0db451764fe1bf5c80 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:25:15 +0100 Subject: [PATCH 0487/1086] Fix member variable name --- .../global/celestial_information.cpp | 166 +++++++++--------- .../global/celestial_information.hpp | 55 +++--- 2 files changed, 112 insertions(+), 109 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 37da06b8d..978fd71c4 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -15,87 +15,88 @@ #include "library/logger/log_utility.hpp" -CelestialInformation::CelestialInformation(std::string inertial_frame, std::string aber_cor, std::string center_obj, RotationMode rotation_mode, - int num_of_selected_body, int* selected_body) - : num_of_selected_body_(num_of_selected_body), - selected_body_(selected_body), - inertial_frame_(inertial_frame), - aber_cor_(aber_cor), - center_obj_(center_obj), +CelestialInformation::CelestialInformation(std::string inertial_frame_name, std::string aberration_correction_setting, std::string center_body_name, + RotationMode rotation_mode, unsigned int number_of_selected_body, int* selected_body_id) + : number_of_selected_body_id_(number_of_selected_body), + selected_body_id_(selected_body_id), + inertial_frame_name_(inertial_frame_name), + aberration_correction_setting_(aberration_correction_setting), + center_body_name_(center_body_name), rotation_mode_(rotation_mode) { // Initialize list - int num_of_state = num_of_selected_body_ * 3; - celes_objects_pos_from_center_i_ = new double[num_of_state]; - celes_objects_vel_from_center_i_ = new double[num_of_state]; - celes_objects_gravity_constant_ = new double[num_of_selected_body_]; - celes_objects_planetographic_radii_m_ = new double[num_of_state]; - celes_objects_mean_radius_m_ = new double[num_of_selected_body_]; + int num_of_state = number_of_selected_body_id_ * 3; + celestial_body_position_from_center_i_m_ = new double[num_of_state]; + celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_id_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_body_id_]; + celestial_body_planetographic_radii_m_ = new double[num_of_state]; // Acquisition of gravity constant - for (int i = 0; i < num_of_selected_body_; i++) { - SpiceInt planet_id = selected_body_[i]; + for (int i = 0; i < number_of_selected_body_id_; i++) { + SpiceInt planet_id = selected_body_id_[i]; SpiceInt dim; - SpiceDouble gravity_constant; - bodvcd_c(planet_id, "GM", 1, &dim, &gravity_constant); + SpiceDouble gravity_constant_km3_s2; + bodvcd_c(planet_id, "GM", 1, &dim, &gravity_constant_km3_s2); // Convert unit [km^3/s^2] to [m^3/s^2] - celes_objects_gravity_constant_[i] = gravity_constant * 1E+9; + celestial_body_gravity_constant_m3_s2_[i] = gravity_constant_km3_s2 * 1E+9; } // Acquisition of radius - for (int i = 0; i < num_of_selected_body_; i++) { - SpiceInt planet_id = selected_body_[i]; + for (int i = 0; i < number_of_selected_body_id_; i++) { + SpiceInt planet_id = selected_body_id_[i]; SpiceInt dim; SpiceDouble radii_km[3]; bodvcd_c(planet_id, "RADII", 3, &dim, (SpiceDouble*)radii_km); for (int j = 0; j < 3; j++) { - celes_objects_planetographic_radii_m_[i * 3 + j] = radii_km[j] * 1000.0; + celestial_body_planetographic_radii_m_[i * 3 + j] = radii_km[j] * 1000.0; } - double rx = celes_objects_planetographic_radii_m_[i * 3]; - double ry = celes_objects_planetographic_radii_m_[i * 3 + 1]; - double rz = celes_objects_planetographic_radii_m_[i * 3 + 2]; + double rx = celestial_body_planetographic_radii_m_[i * 3]; + double ry = celestial_body_planetographic_radii_m_[i * 3 + 1]; + double rz = celestial_body_planetographic_radii_m_[i * 3 + 2]; - celes_objects_mean_radius_m_[i] = pow(rx * ry * rz, 1.0 / 3.0); + celestial_body_mean_radius_m_[i] = pow(rx * ry * rz, 1.0 / 3.0); } // Initialize rotation - EarthRotation_ = new CelestialRotation(rotation_mode_, center_obj_); + earth_rotation_ = new CelestialRotation(rotation_mode_, center_body_name_); } CelestialInformation::CelestialInformation(const CelestialInformation& obj) - : num_of_selected_body_(obj.num_of_selected_body_), - inertial_frame_(obj.inertial_frame_), - aber_cor_(obj.aber_cor_), - center_obj_(obj.center_obj_), + : number_of_selected_body_id_(obj.number_of_selected_body_id_), + inertial_frame_name_(obj.inertial_frame_name_), + aberration_correction_setting_(obj.aberration_correction_setting_), + center_body_name_(obj.center_body_name_), rotation_mode_(obj.rotation_mode_) { - int num_of_state = num_of_selected_body_ * 3; - int sd = sizeof(double); - int si = sizeof(int); - - selected_body_ = new int[num_of_selected_body_]; - celes_objects_pos_from_center_i_ = new double[num_of_state]; - celes_objects_vel_from_center_i_ = new double[num_of_state]; - celes_objects_gravity_constant_ = new double[num_of_selected_body_]; - celes_objects_planetographic_radii_m_ = new double[num_of_state]; - celes_objects_mean_radius_m_ = new double[num_of_selected_body_]; - - memcpy(selected_body_, obj.selected_body_, si * num_of_selected_body_); - memcpy(celes_objects_pos_from_center_i_, obj.celes_objects_pos_from_center_i_, sd * num_of_state); - memcpy(celes_objects_vel_from_center_i_, obj.celes_objects_vel_from_center_i_, sd * num_of_state); - memcpy(celes_objects_gravity_constant_, obj.celes_objects_gravity_constant_, sd * num_of_selected_body_); - memcpy(celes_objects_planetographic_radii_m_, obj.celes_objects_planetographic_radii_m_, sd * num_of_state); - memcpy(celes_objects_mean_radius_m_, obj.celes_objects_mean_radius_m_, sd * num_of_selected_body_); + int num_of_state = number_of_selected_body_id_ * 3; + + selected_body_id_ = new int[number_of_selected_body_id_]; + celestial_body_position_from_center_i_m_ = new double[num_of_state]; + celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_id_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_body_id_]; + celestial_body_planetographic_radii_m_ = new double[num_of_state]; + + int size_i = sizeof(int); + memcpy(selected_body_id_, obj.selected_body_id_, size_i * number_of_selected_body_id_); + + int size_d = sizeof(double); + memcpy(celestial_body_position_from_center_i_m_, obj.celestial_body_position_from_center_i_m_, size_d * num_of_state); + memcpy(celestial_body_velocity_from_center_i_m_s_, obj.celestial_body_velocity_from_center_i_m_s_, size_d * num_of_state); + memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_body_id_); + memcpy(celestial_body_mean_radius_m_, obj.celestial_body_mean_radius_m_, size_d * number_of_selected_body_id_); + memcpy(celestial_body_planetographic_radii_m_, obj.celestial_body_planetographic_radii_m_, size_d * num_of_state); } CelestialInformation::~CelestialInformation() { - delete[] celes_objects_pos_from_center_i_; - delete[] celes_objects_vel_from_center_i_; - delete[] celes_objects_gravity_constant_; - delete[] celes_objects_planetographic_radii_m_; - delete[] celes_objects_mean_radius_m_; - delete[] selected_body_; - delete EarthRotation_; + delete[] celestial_body_position_from_center_i_m_; + delete[] celestial_body_velocity_from_center_i_m_s_; + delete[] celestial_body_gravity_constant_m3_s2_; + delete[] celestial_body_mean_radius_m_; + delete[] celestial_body_planetographic_radii_m_; + delete[] selected_body_id_; + delete earth_rotation_; } void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { @@ -104,8 +105,8 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { std::string jd = "jd " + std::to_string(current_jd); str2et_c(jd.c_str(), &et); - for (int i = 0; i < num_of_selected_body_; i++) { - SpiceInt planet_id = selected_body_[i]; + for (int i = 0; i < number_of_selected_body_id_; i++) { + SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id SpiceBoolean found; @@ -118,27 +119,27 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { GetPlanetOrbit(namebuf, et, (SpiceDouble*)rv_buf); // Convert unit [km], [km/s] to [m], [m/s] for (int j = 0; j < 3; j++) { - celes_objects_pos_from_center_i_[i * 3 + j] = rv_buf[j] * 1000.0; - celes_objects_vel_from_center_i_[i * 3 + j] = rv_buf[j + 3] * 1000.0; + celestial_body_position_from_center_i_m_[i * 3 + j] = rv_buf[j] * 1000.0; + celestial_body_velocity_from_center_i_m_s_[i * 3 + j] = rv_buf[j + 3] * 1000.0; } } // Update CelesRot - EarthRotation_->Update(current_jd); + earth_rotation_->Update(current_jd); } // Getters libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const int id) const { libra::Vector<3> pos(0.0); - if (id > num_of_selected_body_) return pos; - for (int i = 0; i < 3; i++) pos[i] = celes_objects_pos_from_center_i_[id * 3 + i]; + if (id > number_of_selected_body_id_) return pos; + for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; return pos; } libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const int id) const { libra::Vector<3> vel(0.0); - if (id > num_of_selected_body_) return vel; - for (int i = 0; i < 3; i++) vel[i] = celes_objects_vel_from_center_i_[id * 3 + i]; + if (id > number_of_selected_body_id_) return vel; + for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; return vel; } @@ -154,15 +155,15 @@ libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const char* body_name) double CelestialInformation::GetGravityConstant(const char* body_name) const { int index = CalcBodyIdFromName(body_name); - return celes_objects_gravity_constant_[index]; + return celestial_body_gravity_constant_m3_s2_[index]; } -double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_obj_.c_str()); } +double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_body_name_.c_str()); } libra::Vector<3> CelestialInformation::GetRadii(const int id) const { libra::Vector<3> radii(0.0); - if (id > num_of_selected_body_) return radii; - for (int i = 0; i < 3; i++) radii[i] = celes_objects_planetographic_radii_m_[id * 3 + i]; + if (id > number_of_selected_body_id_) return radii; + for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; return radii; } @@ -173,7 +174,7 @@ libra::Vector<3> CelestialInformation::GetRadiiFromName(const char* body_name) c double CelestialInformation::GetMeanRadiusFromName(const char* body_name) const { int index = CalcBodyIdFromName(body_name); - return celes_objects_mean_radius_m_[index]; + return celestial_body_mean_radius_m_[index]; } int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { @@ -183,8 +184,8 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { // Acquisition of ID from body name bodn2c_c(body_name, (SpiceInt*)&planet_id, (SpiceBoolean*)&found); - for (int i = 0; i < num_of_selected_body_; i++) { - if (selected_body_[i] == planet_id) { + for (int i = 0; i < number_of_selected_body_id_; i++) { + if (selected_body_id_[i] == planet_id) { index = i; break; } @@ -197,8 +198,8 @@ std::string CelestialInformation::GetLogHeader() const { const int maxlen = 100; char namebuf[maxlen]; std::string str_tmp = ""; - for (int i = 0; i < num_of_selected_body_; i++) { - SpiceInt planet_id = selected_body_[i]; + for (int i = 0; i < number_of_selected_body_id_; i++) { + SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); std::string name = namebuf; @@ -214,12 +215,12 @@ std::string CelestialInformation::GetLogHeader() const { std::string CelestialInformation::GetLogValue() const { std::string str_tmp = ""; - for (int i = 0; i < num_of_selected_body_; i++) { + for (int i = 0; i < number_of_selected_body_id_; i++) { for (int j = 0; j < 3; j++) { - str_tmp += WriteScalar(celes_objects_pos_from_center_i_[i * 3 + j]); + str_tmp += WriteScalar(celestial_body_position_from_center_i_m_[i * 3 + j]); } for (int j = 0; j < 3; j++) { - str_tmp += WriteScalar(celes_objects_vel_from_center_i_[i * 3 + j]); + str_tmp += WriteScalar(celestial_body_velocity_from_center_i_m_s_[i * 3 + j]); } } return str_tmp; @@ -231,19 +232,19 @@ void CelestialInformation::DebugOutput(void) { char namebuf[maxlen]; std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " "VELx,y,z[m/s] from SC"; - for (int i = 0; i < num_of_selected_body_; i++) { - SpiceInt planet_id = selected_body_[i]; + for (int i = 0; i < number_of_selected_body_id_; i++) { + SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); // cout< Date: Thu, 23 Feb 2023 09:34:56 +0100 Subject: [PATCH 0488/1086] Fix function arguments --- .../global/celestial_information.cpp | 41 ++++++++++--------- .../global/celestial_information.hpp | 16 ++++---- 2 files changed, 29 insertions(+), 28 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 978fd71c4..9fcfd751a 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -15,16 +15,17 @@ #include "library/logger/log_utility.hpp" -CelestialInformation::CelestialInformation(std::string inertial_frame_name, std::string aberration_correction_setting, std::string center_body_name, - RotationMode rotation_mode, unsigned int number_of_selected_body, int* selected_body_id) +CelestialInformation::CelestialInformation(const std::string inertial_frame_name, const std::string aberration_correction_setting, + const std::string center_body_name, const RotationMode rotation_mode, + const unsigned int number_of_selected_body, int* selected_body_id) : number_of_selected_body_id_(number_of_selected_body), selected_body_id_(selected_body_id), inertial_frame_name_(inertial_frame_name), - aberration_correction_setting_(aberration_correction_setting), center_body_name_(center_body_name), + aberration_correction_setting_(aberration_correction_setting), rotation_mode_(rotation_mode) { // Initialize list - int num_of_state = number_of_selected_body_id_ * 3; + unsigned int num_of_state = number_of_selected_body_id_ * 3; celestial_body_position_from_center_i_m_ = new double[num_of_state]; celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_id_]; @@ -32,7 +33,7 @@ CelestialInformation::CelestialInformation(std::string inertial_frame_name, std: celestial_body_planetographic_radii_m_ = new double[num_of_state]; // Acquisition of gravity constant - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { SpiceInt planet_id = selected_body_id_[i]; SpiceInt dim; SpiceDouble gravity_constant_km3_s2; @@ -42,7 +43,7 @@ CelestialInformation::CelestialInformation(std::string inertial_frame_name, std: } // Acquisition of radius - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { SpiceInt planet_id = selected_body_id_[i]; SpiceInt dim; SpiceDouble radii_km[3]; @@ -66,10 +67,10 @@ CelestialInformation::CelestialInformation(std::string inertial_frame_name, std: CelestialInformation::CelestialInformation(const CelestialInformation& obj) : number_of_selected_body_id_(obj.number_of_selected_body_id_), inertial_frame_name_(obj.inertial_frame_name_), - aberration_correction_setting_(obj.aberration_correction_setting_), center_body_name_(obj.center_body_name_), + aberration_correction_setting_(obj.aberration_correction_setting_), rotation_mode_(obj.rotation_mode_) { - int num_of_state = number_of_selected_body_id_ * 3; + unsigned int num_of_state = number_of_selected_body_id_ * 3; selected_body_id_ = new int[number_of_selected_body_id_]; celestial_body_position_from_center_i_m_ = new double[num_of_state]; @@ -78,10 +79,10 @@ CelestialInformation::CelestialInformation(const CelestialInformation& obj) celestial_body_mean_radius_m_ = new double[number_of_selected_body_id_]; celestial_body_planetographic_radii_m_ = new double[num_of_state]; - int size_i = sizeof(int); + size_t size_i = sizeof(int); memcpy(selected_body_id_, obj.selected_body_id_, size_i * number_of_selected_body_id_); - int size_d = sizeof(double); + size_t size_d = sizeof(double); memcpy(celestial_body_position_from_center_i_m_, obj.celestial_body_position_from_center_i_m_, size_d * num_of_state); memcpy(celestial_body_velocity_from_center_i_m_s_, obj.celestial_body_velocity_from_center_i_m_s_, size_d * num_of_state); memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_body_id_); @@ -105,7 +106,7 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { std::string jd = "jd " + std::to_string(current_jd); str2et_c(jd.c_str(), &et); - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id @@ -129,14 +130,14 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { } // Getters -libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const int id) const { +libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const unsigned int id) const { libra::Vector<3> pos(0.0); if (id > number_of_selected_body_id_) return pos; for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; return pos; } -libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const int id) const { +libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const unsigned int id) const { libra::Vector<3> vel(0.0); if (id > number_of_selected_body_id_) return vel; for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; @@ -160,7 +161,7 @@ double CelestialInformation::GetGravityConstant(const char* body_name) const { double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_body_name_.c_str()); } -libra::Vector<3> CelestialInformation::GetRadii(const int id) const { +libra::Vector<3> CelestialInformation::GetRadii(const unsigned int id) const { libra::Vector<3> radii(0.0); if (id > number_of_selected_body_id_) return radii; for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; @@ -184,7 +185,7 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { // Acquisition of ID from body name bodn2c_c(body_name, (SpiceInt*)&planet_id, (SpiceBoolean*)&found); - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { if (selected_body_id_[i] == planet_id) { index = i; break; @@ -198,7 +199,7 @@ std::string CelestialInformation::GetLogHeader() const { const int maxlen = 100; char namebuf[maxlen]; std::string str_tmp = ""; - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); @@ -215,7 +216,7 @@ std::string CelestialInformation::GetLogHeader() const { std::string CelestialInformation::GetLogValue() const { std::string str_tmp = ""; - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celestial_body_position_from_center_i_m_[i * 3 + j]); } @@ -232,14 +233,14 @@ void CelestialInformation::DebugOutput(void) { char namebuf[maxlen]; std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " "VELx,y,z[m/s] from SC"; - for (int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { SpiceInt planet_id = selected_body_id_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); // cout< GetPosFromCenter_i(const int id) const; + libra::Vector<3> GetPosFromCenter_i(const unsigned int id) const; /** * @fn GetPosFromCenter_i * @brief Return position from the center body in the inertial frame [m] @@ -78,7 +78,7 @@ class CelestialInformation : public ILoggable { * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] id: ID of CelestialInformation list */ - libra::Vector<3> GetVelFromCenter_i(const int id) const; + libra::Vector<3> GetVelFromCenter_i(const unsigned int id) const; /** * @fn GetVelFromCenter_i * @brief Return velocity from the center body in the inertial frame [m/s] @@ -105,7 +105,7 @@ class CelestialInformation : public ILoggable { * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - libra::Vector<3> GetRadii(const int id) const; + libra::Vector<3> GetRadii(const unsigned int id) const; /** * @fn GetRadiiFromName * @brief Return 3 axis planetographic radii of a celestial body [m] @@ -124,12 +124,12 @@ class CelestialInformation : public ILoggable { * @fn GetNumBody * @brief Return number of selected body */ - inline unsigned int GetNumBody(void) const { return number_of_selected_body_id_; } + inline int GetNumBody(void) const { return number_of_selected_body_id_; } /** * @fn GetSelectedBody * @brief Return SPICE IDs of selected bodies */ - inline int* GetSelectedBody(void) const { return selected_body_id_; } + inline const int* GetSelectedBody(void) const { return selected_body_id_; } /** * @fn GetCenterBodyName * @brief Return name of the center body @@ -188,7 +188,7 @@ class CelestialInformation : public ILoggable { * @param [in] et: Ephemeris time * @param [out] orbit: Cartesian state vector representing the position and velocity of the target body relative to the specified observer. */ - void GetPlanetOrbit(const char* planet_name, double et, double orbit[6]); + void GetPlanetOrbit(const char* planet_name, const double et, double orbit[6]); }; #endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_INFORMATION_HPP_ From f511f82e617aa11e673c5d785548b482a87cf3ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:36:52 +0100 Subject: [PATCH 0489/1086] Fix function arguments --- src/environment/global/celestial_information.cpp | 6 +++--- src/environment/global/celestial_information.hpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 9fcfd751a..1bd39b438 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -100,10 +100,10 @@ CelestialInformation::~CelestialInformation() { delete earth_rotation_; } -void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { +void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { // Convert time SpiceDouble et; - std::string jd = "jd " + std::to_string(current_jd); + std::string jd = "jd " + std::to_string(current_time_jd); str2et_c(jd.c_str(), &et); for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { @@ -126,7 +126,7 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_jd) { } // Update CelesRot - earth_rotation_->Update(current_jd); + earth_rotation_->Update(current_time_jd); } // Getters diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index df2eb160f..309f5f222 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -56,8 +56,9 @@ class CelestialInformation : public ILoggable { /** * @fn UpdateAllObjectsInfo * @brief Update the information of all selected celestial objects + * @param [in] current_time_jd: Current time [Julian day] */ - void UpdateAllObjectsInfo(const double current_jd); + void UpdateAllObjectsInfo(const double current_time_jd); // Getters // Orbit information From 3e163fa9d5ac6229dcfa3a1b42385dc2c29abbf0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:41:43 +0100 Subject: [PATCH 0490/1086] Replace id to ids --- .../global/celestial_information.cpp | 66 +++++++++---------- .../global/celestial_information.hpp | 12 ++-- .../local/local_celestial_information.cpp | 2 +- 3 files changed, 40 insertions(+), 40 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 1bd39b438..a9ed6ed06 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -17,24 +17,24 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name, const std::string aberration_correction_setting, const std::string center_body_name, const RotationMode rotation_mode, - const unsigned int number_of_selected_body, int* selected_body_id) - : number_of_selected_body_id_(number_of_selected_body), - selected_body_id_(selected_body_id), + const unsigned int number_of_selected_body, int* selected_body_ids) + : number_of_selected_body_ids_(number_of_selected_body), + selected_body_ids_(selected_body_ids), inertial_frame_name_(inertial_frame_name), center_body_name_(center_body_name), aberration_correction_setting_(aberration_correction_setting), rotation_mode_(rotation_mode) { // Initialize list - unsigned int num_of_state = number_of_selected_body_id_ * 3; + unsigned int num_of_state = number_of_selected_body_ids_ * 3; celestial_body_position_from_center_i_m_ = new double[num_of_state]; celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; - celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_id_]; - celestial_body_mean_radius_m_ = new double[number_of_selected_body_id_]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_ids_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_body_ids_]; celestial_body_planetographic_radii_m_ = new double[num_of_state]; // Acquisition of gravity constant - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - SpiceInt planet_id = selected_body_id_[i]; + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + SpiceInt planet_id = selected_body_ids_[i]; SpiceInt dim; SpiceDouble gravity_constant_km3_s2; bodvcd_c(planet_id, "GM", 1, &dim, &gravity_constant_km3_s2); @@ -43,8 +43,8 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name } // Acquisition of radius - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - SpiceInt planet_id = selected_body_id_[i]; + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + SpiceInt planet_id = selected_body_ids_[i]; SpiceInt dim; SpiceDouble radii_km[3]; @@ -65,28 +65,28 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name } CelestialInformation::CelestialInformation(const CelestialInformation& obj) - : number_of_selected_body_id_(obj.number_of_selected_body_id_), + : number_of_selected_body_ids_(obj.number_of_selected_body_ids_), inertial_frame_name_(obj.inertial_frame_name_), center_body_name_(obj.center_body_name_), aberration_correction_setting_(obj.aberration_correction_setting_), rotation_mode_(obj.rotation_mode_) { - unsigned int num_of_state = number_of_selected_body_id_ * 3; + unsigned int num_of_state = number_of_selected_body_ids_ * 3; - selected_body_id_ = new int[number_of_selected_body_id_]; + selected_body_ids_ = new int[number_of_selected_body_ids_]; celestial_body_position_from_center_i_m_ = new double[num_of_state]; celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; - celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_id_]; - celestial_body_mean_radius_m_ = new double[number_of_selected_body_id_]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_ids_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_body_ids_]; celestial_body_planetographic_radii_m_ = new double[num_of_state]; size_t size_i = sizeof(int); - memcpy(selected_body_id_, obj.selected_body_id_, size_i * number_of_selected_body_id_); + memcpy(selected_body_ids_, obj.selected_body_ids_, size_i * number_of_selected_body_ids_); size_t size_d = sizeof(double); memcpy(celestial_body_position_from_center_i_m_, obj.celestial_body_position_from_center_i_m_, size_d * num_of_state); memcpy(celestial_body_velocity_from_center_i_m_s_, obj.celestial_body_velocity_from_center_i_m_s_, size_d * num_of_state); - memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_body_id_); - memcpy(celestial_body_mean_radius_m_, obj.celestial_body_mean_radius_m_, size_d * number_of_selected_body_id_); + memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_body_ids_); + memcpy(celestial_body_mean_radius_m_, obj.celestial_body_mean_radius_m_, size_d * number_of_selected_body_ids_); memcpy(celestial_body_planetographic_radii_m_, obj.celestial_body_planetographic_radii_m_, size_d * num_of_state); } @@ -96,7 +96,7 @@ CelestialInformation::~CelestialInformation() { delete[] celestial_body_gravity_constant_m3_s2_; delete[] celestial_body_mean_radius_m_; delete[] celestial_body_planetographic_radii_m_; - delete[] selected_body_id_; + delete[] selected_body_ids_; delete earth_rotation_; } @@ -106,8 +106,8 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { std::string jd = "jd " + std::to_string(current_time_jd); str2et_c(jd.c_str(), &et); - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - SpiceInt planet_id = selected_body_id_[i]; + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id SpiceBoolean found; @@ -132,14 +132,14 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { // Getters libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const unsigned int id) const { libra::Vector<3> pos(0.0); - if (id > number_of_selected_body_id_) return pos; + if (id > number_of_selected_body_ids_) return pos; for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; return pos; } libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const unsigned int id) const { libra::Vector<3> vel(0.0); - if (id > number_of_selected_body_id_) return vel; + if (id > number_of_selected_body_ids_) return vel; for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; return vel; } @@ -163,7 +163,7 @@ double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { re libra::Vector<3> CelestialInformation::GetRadii(const unsigned int id) const { libra::Vector<3> radii(0.0); - if (id > number_of_selected_body_id_) return radii; + if (id > number_of_selected_body_ids_) return radii; for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; return radii; } @@ -185,8 +185,8 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { // Acquisition of ID from body name bodn2c_c(body_name, (SpiceInt*)&planet_id, (SpiceBoolean*)&found); - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - if (selected_body_id_[i] == planet_id) { + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + if (selected_body_ids_[i] == planet_id) { index = i; break; } @@ -199,8 +199,8 @@ std::string CelestialInformation::GetLogHeader() const { const int maxlen = 100; char namebuf[maxlen]; std::string str_tmp = ""; - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - SpiceInt planet_id = selected_body_id_[i]; + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); std::string name = namebuf; @@ -216,7 +216,7 @@ std::string CelestialInformation::GetLogHeader() const { std::string CelestialInformation::GetLogValue() const { std::string str_tmp = ""; - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celestial_body_position_from_center_i_m_[i * 3 + j]); } @@ -233,15 +233,15 @@ void CelestialInformation::DebugOutput(void) { char namebuf[maxlen]; std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " "VELx,y,z[m/s] from SC"; - for (unsigned int i = 0; i < number_of_selected_body_id_; i++) { - SpiceInt planet_id = selected_body_id_[i]; + for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); // cout<GetNumBody(); i++) { - SpiceInt planet_id = glo_celes_info_->GetSelectedBody()[i]; + SpiceInt planet_id = glo_celes_info_->GetSelectedBodyIds()[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); string name = namebuf; From bfc659f056ed75ffc6c2d6b908f193976f0df065 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:44:17 +0100 Subject: [PATCH 0491/1086] Fix member variable name --- .../global/celestial_information.cpp | 46 +++++++++---------- .../global/celestial_information.hpp | 4 +- 2 files changed, 25 insertions(+), 25 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index a9ed6ed06..0a2b2c00d 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -18,22 +18,22 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name, const std::string aberration_correction_setting, const std::string center_body_name, const RotationMode rotation_mode, const unsigned int number_of_selected_body, int* selected_body_ids) - : number_of_selected_body_ids_(number_of_selected_body), + : number_of_selected_bodies_(number_of_selected_body), selected_body_ids_(selected_body_ids), inertial_frame_name_(inertial_frame_name), center_body_name_(center_body_name), aberration_correction_setting_(aberration_correction_setting), rotation_mode_(rotation_mode) { // Initialize list - unsigned int num_of_state = number_of_selected_body_ids_ * 3; + unsigned int num_of_state = number_of_selected_bodies_ * 3; celestial_body_position_from_center_i_m_ = new double[num_of_state]; celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; - celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_ids_]; - celestial_body_mean_radius_m_ = new double[number_of_selected_body_ids_]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_bodies_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_bodies_]; celestial_body_planetographic_radii_m_ = new double[num_of_state]; // Acquisition of gravity constant - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; SpiceInt dim; SpiceDouble gravity_constant_km3_s2; @@ -43,7 +43,7 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name } // Acquisition of radius - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; SpiceInt dim; SpiceDouble radii_km[3]; @@ -65,28 +65,28 @@ CelestialInformation::CelestialInformation(const std::string inertial_frame_name } CelestialInformation::CelestialInformation(const CelestialInformation& obj) - : number_of_selected_body_ids_(obj.number_of_selected_body_ids_), + : number_of_selected_bodies_(obj.number_of_selected_bodies_), inertial_frame_name_(obj.inertial_frame_name_), center_body_name_(obj.center_body_name_), aberration_correction_setting_(obj.aberration_correction_setting_), rotation_mode_(obj.rotation_mode_) { - unsigned int num_of_state = number_of_selected_body_ids_ * 3; + unsigned int num_of_state = number_of_selected_bodies_ * 3; - selected_body_ids_ = new int[number_of_selected_body_ids_]; + selected_body_ids_ = new int[number_of_selected_bodies_]; celestial_body_position_from_center_i_m_ = new double[num_of_state]; celestial_body_velocity_from_center_i_m_s_ = new double[num_of_state]; - celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_body_ids_]; - celestial_body_mean_radius_m_ = new double[number_of_selected_body_ids_]; + celestial_body_gravity_constant_m3_s2_ = new double[number_of_selected_bodies_]; + celestial_body_mean_radius_m_ = new double[number_of_selected_bodies_]; celestial_body_planetographic_radii_m_ = new double[num_of_state]; size_t size_i = sizeof(int); - memcpy(selected_body_ids_, obj.selected_body_ids_, size_i * number_of_selected_body_ids_); + memcpy(selected_body_ids_, obj.selected_body_ids_, size_i * number_of_selected_bodies_); size_t size_d = sizeof(double); memcpy(celestial_body_position_from_center_i_m_, obj.celestial_body_position_from_center_i_m_, size_d * num_of_state); memcpy(celestial_body_velocity_from_center_i_m_s_, obj.celestial_body_velocity_from_center_i_m_s_, size_d * num_of_state); - memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_body_ids_); - memcpy(celestial_body_mean_radius_m_, obj.celestial_body_mean_radius_m_, size_d * number_of_selected_body_ids_); + memcpy(celestial_body_gravity_constant_m3_s2_, obj.celestial_body_gravity_constant_m3_s2_, size_d * number_of_selected_bodies_); + memcpy(celestial_body_mean_radius_m_, obj.celestial_body_mean_radius_m_, size_d * number_of_selected_bodies_); memcpy(celestial_body_planetographic_radii_m_, obj.celestial_body_planetographic_radii_m_, size_d * num_of_state); } @@ -106,7 +106,7 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { std::string jd = "jd " + std::to_string(current_time_jd); str2et_c(jd.c_str(), &et); - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id @@ -132,14 +132,14 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { // Getters libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const unsigned int id) const { libra::Vector<3> pos(0.0); - if (id > number_of_selected_body_ids_) return pos; + if (id > number_of_selected_bodies_) return pos; for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; return pos; } libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const unsigned int id) const { libra::Vector<3> vel(0.0); - if (id > number_of_selected_body_ids_) return vel; + if (id > number_of_selected_bodies_) return vel; for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; return vel; } @@ -163,7 +163,7 @@ double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { re libra::Vector<3> CelestialInformation::GetRadii(const unsigned int id) const { libra::Vector<3> radii(0.0); - if (id > number_of_selected_body_ids_) return radii; + if (id > number_of_selected_bodies_) return radii; for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; return radii; } @@ -185,7 +185,7 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { // Acquisition of ID from body name bodn2c_c(body_name, (SpiceInt*)&planet_id, (SpiceBoolean*)&found); - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { if (selected_body_ids_[i] == planet_id) { index = i; break; @@ -199,7 +199,7 @@ std::string CelestialInformation::GetLogHeader() const { const int maxlen = 100; char namebuf[maxlen]; std::string str_tmp = ""; - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); @@ -216,7 +216,7 @@ std::string CelestialInformation::GetLogHeader() const { std::string CelestialInformation::GetLogValue() const { std::string str_tmp = ""; - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celestial_body_position_from_center_i_m_[i * 3 + j]); } @@ -233,14 +233,14 @@ void CelestialInformation::DebugOutput(void) { char namebuf[maxlen]; std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " "VELx,y,z[m/s] from SC"; - for (unsigned int i = 0; i < number_of_selected_body_ids_; i++) { + for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); // cout< Date: Thu, 23 Feb 2023 09:45:42 +0100 Subject: [PATCH 0492/1086] Fix function name --- src/environment/global/celestial_information.hpp | 4 ++-- src/environment/local/local_celestial_information.cpp | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 33a1f0796..8cb4cc91d 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -122,10 +122,10 @@ class CelestialInformation : public ILoggable { // Parameters /** - * @fn GetNumBody + * @fn GetNumberOfSelectedBodies * @brief Return number of selected body */ - inline int GetNumBody(void) const { return number_of_selected_bodies_; } + inline int GetNumberOfSelectedBodies(void) const { return number_of_selected_bodies_; } /** * @fn GetSelectedBody * @brief Return SPICE IDs of selected bodies diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 4d221254e..57a49dcdc 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -15,7 +15,7 @@ using namespace std; LocalCelestialInformation::LocalCelestialInformation(const CelestialInformation* glo_celes_info) : glo_celes_info_(glo_celes_info) { - int num_of_state = glo_celes_info_->GetNumBody() * 3; + int num_of_state = glo_celes_info_->GetNumberOfSelectedBodies() * 3; celes_objects_pos_from_center_b_ = new double[num_of_state]; celes_objects_vel_from_center_b_ = new double[num_of_state]; celes_objects_pos_from_sc_i_ = new double[num_of_state]; @@ -45,7 +45,7 @@ LocalCelestialInformation::~LocalCelestialInformation() { void LocalCelestialInformation::UpdateAllObjectsInfo(const Vector<3> sc_pos_from_center_i, const Vector<3> sc_vel_from_center_i, const Quaternion q_i2b, const Vector<3> sc_body_rate) { Vector<3> pos_center_i, vel_center_i; - for (int i = 0; i < glo_celes_info_->GetNumBody(); i++) { + for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { pos_center_i = glo_celes_info_->GetPosFromCenter_i(i); vel_center_i = glo_celes_info_->GetVelFromCenter_i(i); // Change origin of frame @@ -63,7 +63,7 @@ void LocalCelestialInformation::CalcAllPosVel_b(const Quaternion q_i2b, const Ve Vector<3> pos_center_i, vel_center_i; double r_buf1_i[3], v_buf1_i[3], r_buf1_b[3], v_buf1_b[3]; double r_buf2_i[3], v_buf2_i[3], r_buf2_b[3], v_buf2_b[3]; - for (int i = 0; i < glo_celes_info_->GetNumBody(); i++) { + for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { pos_center_i = glo_celes_info_->GetPosFromCenter_i(i); vel_center_i = glo_celes_info_->GetVelFromCenter_i(i); for (int j = 0; j < 3; j++) { @@ -164,7 +164,7 @@ string LocalCelestialInformation::GetLogHeader() const { const int maxlen = 100; char namebuf[maxlen]; string str_tmp = ""; - for (int i = 0; i < glo_celes_info_->GetNumBody(); i++) { + for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { SpiceInt planet_id = glo_celes_info_->GetSelectedBodyIds()[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); @@ -180,7 +180,7 @@ string LocalCelestialInformation::GetLogHeader() const { string LocalCelestialInformation::GetLogValue() const { string str_tmp = ""; - for (int i = 0; i < glo_celes_info_->GetNumBody(); i++) { + for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { for (int j = 0; j < 3; j++) { str_tmp += WriteScalar(celes_objects_pos_from_sc_b_[i * 3 + j]); } From b405f0c70f9a975ce64d97432cb38d1fd96150a1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:53:58 +0100 Subject: [PATCH 0493/1086] Change to inline functions --- .../global/celestial_information.cpp | 49 ------------------- .../global/celestial_information.hpp | 49 +++++++++++++++---- 2 files changed, 40 insertions(+), 58 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 0a2b2c00d..2dce31d97 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -129,55 +129,6 @@ void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { earth_rotation_->Update(current_time_jd); } -// Getters -libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const unsigned int id) const { - libra::Vector<3> pos(0.0); - if (id > number_of_selected_bodies_) return pos; - for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; - return pos; -} - -libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const unsigned int id) const { - libra::Vector<3> vel(0.0); - if (id > number_of_selected_bodies_) return vel; - for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; - return vel; -} - -libra::Vector<3> CelestialInformation::GetPosFromCenter_i(const char* body_name) const { - int id = CalcBodyIdFromName(body_name); - return GetPosFromCenter_i(id); -} - -libra::Vector<3> CelestialInformation::GetVelFromCenter_i(const char* body_name) const { - int id = CalcBodyIdFromName(body_name); - return GetVelFromCenter_i(id); -} - -double CelestialInformation::GetGravityConstant(const char* body_name) const { - int index = CalcBodyIdFromName(body_name); - return celestial_body_gravity_constant_m3_s2_[index]; -} - -double CelestialInformation::GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_body_name_.c_str()); } - -libra::Vector<3> CelestialInformation::GetRadii(const unsigned int id) const { - libra::Vector<3> radii(0.0); - if (id > number_of_selected_bodies_) return radii; - for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; - return radii; -} - -libra::Vector<3> CelestialInformation::GetRadiiFromName(const char* body_name) const { - int id = CalcBodyIdFromName(body_name); - return GetRadii(id); -} - -double CelestialInformation::GetMeanRadiusFromName(const char* body_name) const { - int index = CalcBodyIdFromName(body_name); - return celestial_body_mean_radius_m_[index]; -} - int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { int index = 0; SpiceInt planet_id; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 8cb4cc91d..b5af1de30 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -67,25 +67,42 @@ class CelestialInformation : public ILoggable { * @brief Return position from the center body in the inertial frame [m] * @param [in] id: ID of CelestialInformation list */ - libra::Vector<3> GetPosFromCenter_i(const unsigned int id) const; + inline libra::Vector<3> GetPosFromCenter_i(const unsigned int id) const { + libra::Vector<3> pos(0.0); + if (id > number_of_selected_bodies_) return pos; + for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; + return pos; + } /** * @fn GetPosFromCenter_i * @brief Return position from the center body in the inertial frame [m] * @param [in] body_name: Name of the body defined in the SPICE */ - libra::Vector<3> GetPosFromCenter_i(const char* body_name) const; + inline libra::Vector<3> GetPosFromCenter_i(const char* body_name) const { + int id = CalcBodyIdFromName(body_name); + return GetPosFromCenter_i(id); + } + /** * @fn GetVelFromCenter_i * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] id: ID of CelestialInformation list */ - libra::Vector<3> GetVelFromCenter_i(const unsigned int id) const; + inline libra::Vector<3> GetVelFromCenter_i(const unsigned int id) const { + libra::Vector<3> vel(0.0); + if (id > number_of_selected_bodies_) return vel; + for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; + return vel; + } /** * @fn GetVelFromCenter_i * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] body_name: Name of the body defined in the SPICE */ - libra::Vector<3> GetVelFromCenter_i(const char* body_name) const; + inline libra::Vector<3> GetVelFromCenter_i(const char* body_name) const { + int id = CalcBodyIdFromName(body_name); + return GetVelFromCenter_i(id); + } // Gravity constants /** @@ -93,12 +110,15 @@ class CelestialInformation : public ILoggable { * @brief Return gravity constant of the celestial body [m^3/s^2] * @param [in] body_name: Name of the body defined in the SPICE */ - double GetGravityConstant(const char* body_name) const; + inline double GetGravityConstant(const char* body_name) const { + int index = CalcBodyIdFromName(body_name); + return celestial_body_gravity_constant_m3_s2_[index]; + } /** * @fn GetCenterBodyGravityConstant_m3_s2 * @brief Return gravity constant of the center body [m^3/s^2] */ - double GetCenterBodyGravityConstant_m3_s2(void) const; + inline double GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_body_name_.c_str()); } // Shape information /** @@ -106,19 +126,30 @@ class CelestialInformation : public ILoggable { * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - libra::Vector<3> GetRadii(const unsigned int id) const; + inline libra::Vector<3> GetRadii(const unsigned int id) const { + libra::Vector<3> radii(0.0); + if (id > number_of_selected_bodies_) return radii; + for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; + return radii; + } /** * @fn GetRadiiFromName * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] body_name: Name of the body defined in the SPICE */ - libra::Vector<3> GetRadiiFromName(const char* body_name) const; + inline libra::Vector<3> GetRadiiFromName(const char* body_name) const { + int id = CalcBodyIdFromName(body_name); + return GetRadii(id); + } /** * @fn GetMeanRadiusFromName * @brief Return mean radius of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - double GetMeanRadiusFromName(const char* body_name) const; + inline double GetMeanRadiusFromName(const char* body_name) const { + int index = CalcBodyIdFromName(body_name); + return celestial_body_mean_radius_m_[index]; + } // Parameters /** From 2563b9750faf9e227bebf93a4540f2b53e1ae784 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 09:58:23 +0100 Subject: [PATCH 0494/1086] Fix function name --- src/disturbances/third_body_gravity.cpp | 2 +- src/environment/global/celestial_information.hpp | 12 ++++++------ .../local/solar_radiation_pressure_environment.cpp | 4 ++-- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 49b0b9cff..b32e64181 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -19,7 +19,7 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D for (auto third_body : third_body_list_) { libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelesInfo().GetPosFromSC_i(third_body.c_str()); libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; - double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant(third_body.c_str()); + double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant_m3_s2(third_body.c_str()); third_body_acceleration_i_m_s2_ = CalcAcceleration_i_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index b5af1de30..1259b0c0a 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -110,7 +110,7 @@ class CelestialInformation : public ILoggable { * @brief Return gravity constant of the celestial body [m^3/s^2] * @param [in] body_name: Name of the body defined in the SPICE */ - inline double GetGravityConstant(const char* body_name) const { + inline double GetGravityConstant_m3_s2(const char* body_name) const { int index = CalcBodyIdFromName(body_name); return celestial_body_gravity_constant_m3_s2_[index]; } @@ -118,7 +118,7 @@ class CelestialInformation : public ILoggable { * @fn GetCenterBodyGravityConstant_m3_s2 * @brief Return gravity constant of the center body [m^3/s^2] */ - inline double GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant(center_body_name_.c_str()); } + inline double GetCenterBodyGravityConstant_m3_s2(void) const { return GetGravityConstant_m3_s2(center_body_name_.c_str()); } // Shape information /** @@ -126,7 +126,7 @@ class CelestialInformation : public ILoggable { * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - inline libra::Vector<3> GetRadii(const unsigned int id) const { + inline libra::Vector<3> GetRadii_m(const unsigned int id) const { libra::Vector<3> radii(0.0); if (id > number_of_selected_bodies_) return radii; for (int i = 0; i < 3; i++) radii[i] = celestial_body_planetographic_radii_m_[id * 3 + i]; @@ -137,16 +137,16 @@ class CelestialInformation : public ILoggable { * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] body_name: Name of the body defined in the SPICE */ - inline libra::Vector<3> GetRadiiFromName(const char* body_name) const { + inline libra::Vector<3> GetRadiiFromName_m(const char* body_name) const { int id = CalcBodyIdFromName(body_name); - return GetRadii(id); + return GetRadii_m(id); } /** * @fn GetMeanRadiusFromName * @brief Return mean radius of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ - inline double GetMeanRadiusFromName(const char* body_name) const { + inline double GetMeanRadiusFromName_m(const char* body_name) const { int index = CalcBodyIdFromName(body_name); return celestial_body_mean_radius_m_[index]; } diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 21f74dad4..6c2c500a6 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -19,7 +19,7 @@ SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : lo solar_constant_ = 1366.0; // [W/m2] pressure_ = solar_constant_ / environment::speed_of_light_m_s; // [N/m2] shadow_source_name_ = local_celes_info_->GetGlobalInfo().GetCenterBodyName(); - sun_radius_m_ = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName("SUN"); + sun_radius_m_ = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName_m("SUN"); } void SRPEnvironment::UpdateAllStates() { @@ -72,7 +72,7 @@ void SRPEnvironment::CalcShadowCoefficient(string shadow_source_name) { const Vector<3> r_sc2sun_eci = local_celes_info_->GetPosFromSC_i("SUN"); const Vector<3> r_sc2source_eci = local_celes_info_->GetPosFromSC_i(shadow_source_name.c_str()); - const double shadow_source_radius_m = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName(shadow_source_name.c_str()); + const double shadow_source_radius_m = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName_m(shadow_source_name.c_str()); const double distance_sat_to_sun = norm(r_sc2sun_eci); const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun From f288389d73dcd974bcc8587ceadd7960d3301cd6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:00:39 +0100 Subject: [PATCH 0495/1086] Fix function name --- .../global/celestial_information.hpp | 20 +++++++++---------- .../local/local_celestial_information.cpp | 8 ++++---- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 1259b0c0a..662d5a42c 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -63,45 +63,45 @@ class CelestialInformation : public ILoggable { // Getters // Orbit information /** - * @fn GetPosFromCenter_i + * @fn GetPositionFromCenter_i_m * @brief Return position from the center body in the inertial frame [m] * @param [in] id: ID of CelestialInformation list */ - inline libra::Vector<3> GetPosFromCenter_i(const unsigned int id) const { + inline libra::Vector<3> GetPositionFromCenter_i_m(const unsigned int id) const { libra::Vector<3> pos(0.0); if (id > number_of_selected_bodies_) return pos; for (int i = 0; i < 3; i++) pos[i] = celestial_body_position_from_center_i_m_[id * 3 + i]; return pos; } /** - * @fn GetPosFromCenter_i + * @fn GetPositionFromCenter_i_m * @brief Return position from the center body in the inertial frame [m] * @param [in] body_name: Name of the body defined in the SPICE */ - inline libra::Vector<3> GetPosFromCenter_i(const char* body_name) const { + inline libra::Vector<3> GetPositionFromCenter_i_m(const char* body_name) const { int id = CalcBodyIdFromName(body_name); - return GetPosFromCenter_i(id); + return GetPositionFromCenter_i_m(id); } /** - * @fn GetVelFromCenter_i + * @fn GetVelocityFromCenter_i_m_s * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] id: ID of CelestialInformation list */ - inline libra::Vector<3> GetVelFromCenter_i(const unsigned int id) const { + inline libra::Vector<3> GetVelocityFromCenter_i_m_s(const unsigned int id) const { libra::Vector<3> vel(0.0); if (id > number_of_selected_bodies_) return vel; for (int i = 0; i < 3; i++) vel[i] = celestial_body_velocity_from_center_i_m_s_[id * 3 + i]; return vel; } /** - * @fn GetVelFromCenter_i + * @fn GetVelocityFromCenter_i_m_s * @brief Return velocity from the center body in the inertial frame [m/s] * @param [in] body_name: Name of the body defined in the SPICE */ - inline libra::Vector<3> GetVelFromCenter_i(const char* body_name) const { + inline libra::Vector<3> GetVelocityFromCenter_i_m_s(const char* body_name) const { int id = CalcBodyIdFromName(body_name); - return GetVelFromCenter_i(id); + return GetVelocityFromCenter_i_m_s(id); } // Gravity constants diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 57a49dcdc..6300f187f 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -46,8 +46,8 @@ void LocalCelestialInformation::UpdateAllObjectsInfo(const Vector<3> sc_pos_from const Quaternion q_i2b, const Vector<3> sc_body_rate) { Vector<3> pos_center_i, vel_center_i; for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = glo_celes_info_->GetPosFromCenter_i(i); - vel_center_i = glo_celes_info_->GetVelFromCenter_i(i); + pos_center_i = glo_celes_info_->GetPositionFromCenter_i_m(i); + vel_center_i = glo_celes_info_->GetVelocityFromCenter_i_m_s(i); // Change origin of frame for (int j = 0; j < 3; j++) { celes_objects_pos_from_sc_i_[i * 3 + j] = pos_center_i[j] - sc_pos_from_center_i[j]; @@ -64,8 +64,8 @@ void LocalCelestialInformation::CalcAllPosVel_b(const Quaternion q_i2b, const Ve double r_buf1_i[3], v_buf1_i[3], r_buf1_b[3], v_buf1_b[3]; double r_buf2_i[3], v_buf2_i[3], r_buf2_b[3], v_buf2_b[3]; for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = glo_celes_info_->GetPosFromCenter_i(i); - vel_center_i = glo_celes_info_->GetVelFromCenter_i(i); + pos_center_i = glo_celes_info_->GetPositionFromCenter_i_m(i); + vel_center_i = glo_celes_info_->GetVelocityFromCenter_i_m_s(i); for (int j = 0; j < 3; j++) { r_buf1_i[j] = pos_center_i[j]; r_buf2_i[j] = celes_objects_pos_from_sc_i_[i * 3 + j]; From 2d8cfe8cc54dd6f47e9e414e82ccd3c17b1adf92 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:01:39 +0100 Subject: [PATCH 0496/1086] Fix comments --- src/environment/global/celestial_information.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index 662d5a42c..d2aeb4e24 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -106,7 +106,7 @@ class CelestialInformation : public ILoggable { // Gravity constants /** - * @fn GetGravityConstant + * @fn GetGravityConstant_m3_s2 * @brief Return gravity constant of the celestial body [m^3/s^2] * @param [in] body_name: Name of the body defined in the SPICE */ @@ -122,7 +122,7 @@ class CelestialInformation : public ILoggable { // Shape information /** - * @fn GetRadii + * @fn GetRadii_m * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ @@ -133,7 +133,7 @@ class CelestialInformation : public ILoggable { return radii; } /** - * @fn GetRadiiFromName + * @fn GetRadiiFromName_m * @brief Return 3 axis planetographic radii of a celestial body [m] * @param [in] body_name: Name of the body defined in the SPICE */ @@ -142,7 +142,7 @@ class CelestialInformation : public ILoggable { return GetRadii_m(id); } /** - * @fn GetMeanRadiusFromName + * @fn GetMeanRadiusFromName_m * @brief Return mean radius of a celestial body [m] * @param [in] id: ID of CelestialInformation list */ From 4f3e24c21da5bb1f25061ab53cb4f094bc0f1632 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:11:31 +0100 Subject: [PATCH 0497/1086] Fix veriables name in local functions --- .../global/celestial_information.cpp | 57 ++++++------------- 1 file changed, 18 insertions(+), 39 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 2dce31d97..24f578eba 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -102,30 +102,31 @@ CelestialInformation::~CelestialInformation() { void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { // Convert time - SpiceDouble et; - std::string jd = "jd " + std::to_string(current_time_jd); - str2et_c(jd.c_str(), &et); + SpiceDouble ephemeris_time; + std::string julian_date = "jd " + std::to_string(current_time_jd); + str2et_c(julian_date.c_str(), &ephemeris_time); + // Update celestial body orbit for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id SpiceBoolean found; - const int maxlen = 100; - char namebuf[maxlen]; - bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); + const int kMaxNameLength = 100; + char name_buffer[kMaxNameLength]; + bodc2n_c(planet_id, kMaxNameLength, name_buffer, (SpiceBoolean*)&found); // Acquisition of position and velocity - SpiceDouble rv_buf[6]; - GetPlanetOrbit(namebuf, et, (SpiceDouble*)rv_buf); + SpiceDouble orbit_buffer_km[6]; + GetPlanetOrbit(name_buffer, ephemeris_time, (SpiceDouble*)orbit_buffer_km); // Convert unit [km], [km/s] to [m], [m/s] for (int j = 0; j < 3; j++) { - celestial_body_position_from_center_i_m_[i * 3 + j] = rv_buf[j] * 1000.0; - celestial_body_velocity_from_center_i_m_s_[i * 3 + j] = rv_buf[j + 3] * 1000.0; + celestial_body_position_from_center_i_m_[i * 3 + j] = orbit_buffer_km[j] * 1000.0; + celestial_body_velocity_from_center_i_m_s_[i * 3 + j] = orbit_buffer_km[j + 3] * 1000.0; } } - // Update CelesRot + // Update celestial rotation earth_rotation_->Update(current_time_jd); } @@ -147,14 +148,14 @@ int CelestialInformation::CalcBodyIdFromName(const char* body_name) const { std::string CelestialInformation::GetLogHeader() const { SpiceBoolean found; - const int maxlen = 100; - char namebuf[maxlen]; + const int kMaxNameLength = 100; + char name_buffer[kMaxNameLength]; std::string str_tmp = ""; for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { SpiceInt planet_id = selected_body_ids_[i]; // Acquisition of body name from id - bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); - std::string name = namebuf; + bodc2n_c(planet_id, kMaxNameLength, name_buffer, (SpiceBoolean*)&found); + std::string name = name_buffer; std::transform(name.begin(), name.end(), name.begin(), ::tolower); std::string body_pos = name + "_position"; std::string body_vel = name + "_velocity"; @@ -178,32 +179,10 @@ std::string CelestialInformation::GetLogValue() const { return str_tmp; } -void CelestialInformation::DebugOutput(void) { - SpiceBoolean found; - const int maxlen = 100; - char namebuf[maxlen]; - std::cout << "BODY NAME, POSx,y,z[m], VELx,y,z[m/s] from CENTER;\nPOSx,y,z[m], " - "VELx,y,z[m/s] from SC"; - for (unsigned int i = 0; i < number_of_selected_bodies_; i++) { - SpiceInt planet_id = selected_body_ids_[i]; - // Acquisition of body name from id - bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); - // cout< Date: Thu, 23 Feb 2023 10:15:45 +0100 Subject: [PATCH 0498/1086] Remove using and unnecessary include files --- src/environment/global/celestial_rotation.cpp | 46 +++++++++---------- src/environment/global/celestial_rotation.hpp | 34 ++++++-------- 2 files changed, 35 insertions(+), 45 deletions(-) diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 8e343817a..5b656928a 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -9,17 +9,15 @@ #include "celestial_rotation.hpp" -#include // for jday() -#include // for gstime() - #include -#include #include -using namespace std; +#include "library/external/sgp4/sgp4ext.h" // for jday() +#include "library/external/sgp4/sgp4unit.h" // for gstime() +#include "library/math/constants.hpp" // Default constructor -CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const string center_obj) { +CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_obj) { planet_name_ = "Anonymous"; rotation_mode_ = Idle; unitalize(DCM_J2000toXCXF_); @@ -30,7 +28,7 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const str } // Initialize the class CelestialRotation instance as Earth -void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotation_mode, const string center_obj) { +void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotation_mode, const std::string center_obj) { planet_name_ = "EARTH"; if (center_obj == planet_name_) { if (rotation_mode == Simple) { @@ -140,10 +138,10 @@ void CelestialRotation::Update(const double JulianDate) { tTT_century[i + 1] = tTT_century[i] * tTT_century[0]; } - Matrix<3, 3> P; - Matrix<3, 3> N; - Matrix<3, 3> R; - Matrix<3, 3> W; + libra::Matrix<3, 3> P; + libra::Matrix<3, 3> N; + libra::Matrix<3, 3> R; + libra::Matrix<3, 3> W; // Nutation + Precession P = Precession(tTT_century); N = Nutation(tTT_century); // epsi_rad_, depsilon_rad_, dpsi_rad_ are @@ -169,9 +167,9 @@ void CelestialRotation::Update(const double JulianDate) { } } -Matrix<3, 3> CelestialRotation::AxialRotation(const double GAST_rad) { return libra::rotz(GAST_rad); } +libra::Matrix<3, 3> CelestialRotation::AxialRotation(const double GAST_rad) { return libra::rotz(GAST_rad); } -Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) { +libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) { // Mean obliquity of the ecliptic epsi_rad_ = c_epsi_rad_[0]; for (int i = 0; i < 3; i++) { @@ -223,17 +221,17 @@ Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) { c_depsilon_rad_[7] * cos(2 * L_rad + lm_rad) + c_depsilon_rad_[8] * cos(2 * Ld_rad - ls_rad); // [rad] double epsi_mod_rad = epsi_rad_ + depsilon_rad_; - Matrix<3, 3> X_epsi_1st = libra::rotx(epsi_rad_); - Matrix<3, 3> Z_dpsi = libra::rotz(-dpsi_rad_); - Matrix<3, 3> X_epsi_2nd = libra::rotx(-epsi_mod_rad); + libra::Matrix<3, 3> X_epsi_1st = libra::rotx(epsi_rad_); + libra::Matrix<3, 3> Z_dpsi = libra::rotz(-dpsi_rad_); + libra::Matrix<3, 3> X_epsi_2nd = libra::rotx(-epsi_mod_rad); - Matrix<3, 3> N; + libra::Matrix<3, 3> N; N = X_epsi_2nd * Z_dpsi * X_epsi_1st; return N; } -Matrix<3, 3> CelestialRotation::Precession(const double (&tTT_century)[4]) { +libra::Matrix<3, 3> CelestialRotation::Precession(const double (&tTT_century)[4]) { // Compute precession angles(zeta, theta, z) double zeta_rad = 0.0; for (int i = 0; i < 3; i++) { @@ -249,18 +247,18 @@ Matrix<3, 3> CelestialRotation::Precession(const double (&tTT_century)[4]) { } // Develop transformation matrix - Matrix<3, 3> Z_zeta = libra::rotz(-zeta_rad); - Matrix<3, 3> Y_theta = libra::roty(theta_rad); - Matrix<3, 3> Z_z = libra::rotz(-z_rad); + libra::Matrix<3, 3> Z_zeta = libra::rotz(-zeta_rad); + libra::Matrix<3, 3> Y_theta = libra::roty(theta_rad); + libra::Matrix<3, 3> Z_z = libra::rotz(-z_rad); - Matrix<3, 3> P; + libra::Matrix<3, 3> P; P = Z_z * Y_theta * Z_zeta; return P; } -Matrix<3, 3> CelestialRotation::PolarMotion(const double Xp, const double Yp) { - Matrix<3, 3> W; +libra::Matrix<3, 3> CelestialRotation::PolarMotion(const double Xp, const double Yp) { + libra::Matrix<3, 3> W; W[0][0] = 1.0; W[0][1] = 0.0; diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index bebadde02..39fadec7c 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,16 +10,8 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ -#include #include #include -#include -#include -#include -#include - -using libra::Quaternion; -using libra::Vector; /** * @enum RotationMode @@ -58,13 +50,13 @@ class CelestialRotation { * @fn GetDCMJ2000toXCXF * @brief Return the DCM between J2000 inertial frame and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const Matrix<3, 3> GetDCMJ2000toXCXF() const { return DCM_J2000toXCXF_; }; + inline const libra::Matrix<3, 3> GetDCMJ2000toXCXF() const { return DCM_J2000toXCXF_; }; /** * @fn GetDCMJ2000toXCXF * @brief Return the DCM between TEME (Inertial frame used in SGP4) and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const Matrix<3, 3> GetDCMTEMEtoXCXF() const { return DCM_TEMEtoXCXF_; }; + inline const libra::Matrix<3, 3> GetDCMTEMEtoXCXF() const { return DCM_TEMEtoXCXF_; }; private: /** @@ -76,18 +68,18 @@ class CelestialRotation { */ void Init_CelestialRotation_As_Earth(const RotationMode rotation_mode, const std::string center_obj); - Matrix<3, 3> AxialRotation(const double GAST_rad); //!< Movement of the coordinate axes due to rotation around the rotation axis - Matrix<3, 3> Nutation(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Nutation - Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession - Matrix<3, 3> PolarMotion(const double Xp, const double Yp); //!< Movement of the coordinate axes due to Polar Motion + libra::Matrix<3, 3> AxialRotation(const double GAST_rad); //!< Movement of the coordinate axes due to rotation around the rotation axis + libra::Matrix<3, 3> Nutation(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Nutation + libra::Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession + libra::Matrix<3, 3> PolarMotion(const double Xp, const double Yp); //!< Movement of the coordinate axes due to Polar Motion - double dpsi_rad_; //!< Nutation in obliquity [rad] - double depsilon_rad_; //!< Nutation in longitude [rad] - double epsi_rad_; //!< Mean obliquity of the ecliptic [rad] - Matrix<3, 3> DCM_J2000toXCXF_; //!< Direction Cosine Matrix J2000 to XCXF(X-Centered X-Fixed) - Matrix<3, 3> DCM_TEMEtoXCXF_; //!< Direction Cosine Matrix TEME to XCXF(X-Centered X-Fixed) - RotationMode rotation_mode_; //!< Designation of dynamics model - std::string planet_name_; //!< Designate which solar planet the instance should work as + double dpsi_rad_; //!< Nutation in obliquity [rad] + double depsilon_rad_; //!< Nutation in longitude [rad] + double epsi_rad_; //!< Mean obliquity of the ecliptic [rad] + libra::Matrix<3, 3> DCM_J2000toXCXF_; //!< Direction Cosine Matrix J2000 to XCXF(X-Centered X-Fixed) + libra::Matrix<3, 3> DCM_TEMEtoXCXF_; //!< Direction Cosine Matrix TEME to XCXF(X-Centered X-Fixed) + RotationMode rotation_mode_; //!< Designation of dynamics model + std::string planet_name_; //!< Designate which solar planet the instance should work as // Definitions of coefficeints // They are handling as constant values From 5ab4bc06c5656fd40bbb4eccef812efedaf760ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:27:51 +0100 Subject: [PATCH 0499/1086] Fix member variable names --- src/environment/global/celestial_rotation.cpp | 138 +++++++++--------- src/environment/global/celestial_rotation.hpp | 55 +++---- 2 files changed, 97 insertions(+), 96 deletions(-) diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 5b656928a..1e3474832 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -20,8 +20,8 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_obj) { planet_name_ = "Anonymous"; rotation_mode_ = Idle; - unitalize(DCM_J2000toXCXF_); - DCM_TEMEtoXCXF_ = DCM_J2000toXCXF_; + unitalize(dcm_j2000_to_xcxf_); + dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; if (center_obj == "EARTH") { Init_CelestialRotation_As_Earth(rotation_mode, center_obj); } @@ -41,10 +41,10 @@ void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotat // Coefficients to compute mean obliquity of the ecliptic // The actual unit of the coefficients are [rad/century^i], where i is the index of the array - c_epsi_rad_[0] = 23.4392911 * libra::deg_to_rad; // [rad] - c_epsi_rad_[1] = -46.8150000 * libra::arcsec_to_rad; // [rad/century] - c_epsi_rad_[2] = -5.9000e-4 * libra::arcsec_to_rad; // [rad/century^2] - c_epsi_rad_[3] = 1.8130e-3 * libra::arcsec_to_rad; // [rad/century^3] + c_epsilon_rad_[0] = 23.4392911 * libra::deg_to_rad; // [rad] + c_epsilon_rad_[1] = -46.8150000 * libra::arcsec_to_rad; // [rad/century] + c_epsilon_rad_[2] = -5.9000e-4 * libra::arcsec_to_rad; // [rad/century^2] + c_epsilon_rad_[3] = 1.8130e-3 * libra::arcsec_to_rad; // [rad/century^3] // Coefficients to compute delauney angles // The actual unit of the coefficients are [rad/century^i], where i is the index of the array @@ -60,44 +60,44 @@ void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotat c_ls_rad_[3] = 0.00013600 * libra::arcsec_to_rad; // [rad/century^3] c_ls_rad_[4] = -0.00001149 * libra::arcsec_to_rad; // [rad/century^4] - c_F_rad_[0] = 93.27209062 * libra::deg_to_rad; // [rad] - c_F_rad_[1] = 1739527262.84780000 * libra::arcsec_to_rad; // [rad/century] - c_F_rad_[2] = -12.75120000 * libra::arcsec_to_rad; // [rad/century^2] - c_F_rad_[3] = -0.00103700 * libra::arcsec_to_rad; // [rad/century^3] - c_F_rad_[4] = 0.00000417 * libra::arcsec_to_rad; // [rad/century^4] + c_f_rad_[0] = 93.27209062 * libra::deg_to_rad; // [rad] + c_f_rad_[1] = 1739527262.84780000 * libra::arcsec_to_rad; // [rad/century] + c_f_rad_[2] = -12.75120000 * libra::arcsec_to_rad; // [rad/century^2] + c_f_rad_[3] = -0.00103700 * libra::arcsec_to_rad; // [rad/century^3] + c_f_rad_[4] = 0.00000417 * libra::arcsec_to_rad; // [rad/century^4] - c_D_rad_[0] = 297.85019547 * libra::deg_to_rad; // [rad] - c_D_rad_[1] = 1602961601.20900000 * libra::arcsec_to_rad; // [rad/century] - c_D_rad_[2] = -6.37060000 * libra::arcsec_to_rad; // [rad/century^2] - c_D_rad_[3] = 0.00659300 * libra::arcsec_to_rad; // [rad/century^3] - c_D_rad_[4] = -0.00003169 * libra::arcsec_to_rad; // [rad/century^4] + c_d_rad_[0] = 297.85019547 * libra::deg_to_rad; // [rad] + c_d_rad_[1] = 1602961601.20900000 * libra::arcsec_to_rad; // [rad/century] + c_d_rad_[2] = -6.37060000 * libra::arcsec_to_rad; // [rad/century^2] + c_d_rad_[3] = 0.00659300 * libra::arcsec_to_rad; // [rad/century^3] + c_d_rad_[4] = -0.00003169 * libra::arcsec_to_rad; // [rad/century^4] - c_O_rad_[0] = 125.04455501 * libra::deg_to_rad; // [rad] - c_O_rad_[1] = -6962890.54310000 * libra::arcsec_to_rad; // [rad/century] - c_O_rad_[2] = 7.47220000 * libra::arcsec_to_rad; // [rad/century^2] - c_O_rad_[3] = 0.00770200 * libra::arcsec_to_rad; // [rad/century^3] - c_O_rad_[4] = -0.00005939 * libra::arcsec_to_rad; // [rad/century^4] + c_o_rad_[0] = 125.04455501 * libra::deg_to_rad; // [rad] + c_o_rad_[1] = -6962890.54310000 * libra::arcsec_to_rad; // [rad/century] + c_o_rad_[2] = 7.47220000 * libra::arcsec_to_rad; // [rad/century^2] + c_o_rad_[3] = 0.00770200 * libra::arcsec_to_rad; // [rad/century^3] + c_o_rad_[4] = -0.00005939 * libra::arcsec_to_rad; // [rad/century^4] // Coefficients to compute nutation angles - c_depsilon_rad_[0] = 9.2050 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[1] = 0.5730 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[2] = -0.0900 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[3] = 0.0980 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[4] = 0.0070 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[5] = -0.0010 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[6] = 0.0220 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[7] = 0.0130 * libra::arcsec_to_rad; // [rad] - c_depsilon_rad_[8] = -0.0100 * libra::arcsec_to_rad; // [rad] - - c_dpsi_rad_[0] = -17.2060 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[1] = -1.3170 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[2] = 0.2070 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[3] = -0.2280 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[4] = 0.1480 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[5] = 0.0710 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[6] = -0.0520 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[7] = -0.0300 * libra::arcsec_to_rad; // [rad] - c_dpsi_rad_[8] = 0.0220 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[0] = 9.2050 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[1] = 0.5730 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[2] = -0.0900 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[3] = 0.0980 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[4] = 0.0070 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[5] = -0.0010 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[6] = 0.0220 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[7] = 0.0130 * libra::arcsec_to_rad; // [rad] + c_d_epsilon_rad_[8] = -0.0100 * libra::arcsec_to_rad; // [rad] + + c_d_psi_rad_[0] = -17.2060 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[1] = -1.3170 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[2] = 0.2070 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[3] = -0.2280 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[4] = 0.1480 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[5] = 0.0710 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[6] = -0.0520 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[7] = -0.0300 * libra::arcsec_to_rad; // [rad] + c_d_psi_rad_[8] = 0.0220 * libra::arcsec_to_rad; // [rad] // Coefficients to compute precession angle // The actual unit of the coefficients are [rad/century^i], where i is the index of the array @@ -115,12 +115,12 @@ void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotat } else { // If the rotation mode is neither Simple nor Full, disable the rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - unitalize(DCM_J2000toXCXF_); + unitalize(dcm_j2000_to_xcxf_); } } else { // If the center object is not the Earth, disable the Earth's rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - unitalize(DCM_J2000toXCXF_); + unitalize(dcm_j2000_to_xcxf_); } } @@ -129,11 +129,11 @@ void CelestialRotation::Update(const double JulianDate) { if (rotation_mode_ == Full) { // Compute Julian date for terestrial time - double jdTT_day = JulianDate + dtUT1UTC_ * kSec2Day; // TODO: Check the correctness. Problem is thtat S2E doesn't have Gregorian calendar. + double jdTT_day = JulianDate + kDtUt1Utc_ * kSec2Day_; // TODO: Check the correctness. Problem is thtat S2E doesn't have Gregorian calendar. // Compute nth power of julian century for terrestrial time the actual unit of tTT_century is [century^(i+1)], i is the index of the array double tTT_century[4]; - tTT_century[0] = (jdTT_day - kJulianDateJ2000) / kDayJulianCentury; + tTT_century[0] = (jdTT_day - kJulianDateJ2000_) / kDayJulianCentury_; for (int i = 0; i < 3; i++) { tTT_century[i + 1] = tTT_century[i] * tTT_century[0]; } @@ -144,12 +144,12 @@ void CelestialRotation::Update(const double JulianDate) { libra::Matrix<3, 3> W; // Nutation + Precession P = Precession(tTT_century); - N = Nutation(tTT_century); // epsi_rad_, depsilon_rad_, dpsi_rad_ are + N = Nutation(tTT_century); // epsilon_rad_, d_epsilon_rad_, d_psi_rad_ are // updated in this proccedure // Axial Rotation - double Eq_rad = dpsi_rad_ * cos(epsi_rad_ + depsilon_rad_); // Equation of equinoxes [rad] - double gast_rad = gmst_rad + Eq_rad; // Greenwitch 'Appearent' Sidereal Time [rad] + double Eq_rad = d_psi_rad_ * cos(epsilon_rad_ + d_epsilon_rad_); // Equation of equinoxes [rad] + double gast_rad = gmst_rad + Eq_rad; // Greenwitch 'Appearent' Sidereal Time [rad] R = AxialRotation(gast_rad); // Polar motion (isnot considered so far, even without polar motion, the result agrees well with the matlab reference) double Xp = 0.0; @@ -157,10 +157,10 @@ void CelestialRotation::Update(const double JulianDate) { W = PolarMotion(Xp, Yp); // Total orientation - DCM_J2000toXCXF_ = W * R * N * P; + dcm_j2000_to_xcxf_ = W * R * N * P; } else if (rotation_mode_ == Simple) { // In this case, only Axial Rotation is executed, with its argument replaced from G'A'ST to G'M'ST - DCM_J2000toXCXF_ = AxialRotation(gmst_rad); + dcm_j2000_to_xcxf_ = AxialRotation(gmst_rad); } else { // Leave the DCM as unit Matrix(diag{1,1,1}) return; @@ -171,9 +171,9 @@ libra::Matrix<3, 3> CelestialRotation::AxialRotation(const double GAST_rad) { re libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) { // Mean obliquity of the ecliptic - epsi_rad_ = c_epsi_rad_[0]; + epsilon_rad_ = c_epsilon_rad_[0]; for (int i = 0; i < 3; i++) { - epsi_rad_ += c_epsi_rad_[i + 1] * tTT_century[i]; + epsilon_rad_ += c_epsilon_rad_[i + 1] * tTT_century[i]; } // Compute five delauney angles(l=lm,l'=ls,F,D,Ω=O) @@ -188,19 +188,19 @@ libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) ls_rad += c_ls_rad_[i + 1] * tTT_century[i]; } // Mean longitude of the moon - mean longitude of ascending node of the moon - double F_rad = c_F_rad_[0]; + double F_rad = c_f_rad_[0]; for (int i = 0; i < 4; i++) { - F_rad += c_F_rad_[i + 1] * tTT_century[i]; + F_rad += c_f_rad_[i + 1] * tTT_century[i]; } // Mean elogation of the moon from the sun - double D_rad = c_D_rad_[0]; + double D_rad = c_d_rad_[0]; for (int i = 0; i < 4; i++) { - D_rad += c_D_rad_[i + 1] * tTT_century[i]; + D_rad += c_d_rad_[i + 1] * tTT_century[i]; } // Mean longitude of ascending node of the moon - double O_rad = c_O_rad_[0]; + double O_rad = c_o_rad_[0]; for (int i = 0; i < 4; i++) { - O_rad += c_O_rad_[i + 1] * tTT_century[i]; + O_rad += c_o_rad_[i + 1] * tTT_century[i]; } // Additional angles @@ -209,20 +209,20 @@ libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) // Compute luni-solar nutation // Nutation in obliquity - dpsi_rad_ = c_dpsi_rad_[0] * sin(O_rad) + c_dpsi_rad_[1] * sin(2 * Ld_rad) + c_dpsi_rad_[2] * sin(2 * O_rad) + c_dpsi_rad_[3] * sin(2 * L_rad) + - c_dpsi_rad_[4] * sin(ls_rad); // [rad] - dpsi_rad_ = dpsi_rad_ + c_dpsi_rad_[5] * sin(lm_rad) + c_dpsi_rad_[6] * sin(2 * Ld_rad + ls_rad) + c_dpsi_rad_[7] * sin(2 * L_rad + lm_rad) + - c_dpsi_rad_[8] * sin(2 * Ld_rad - ls_rad); // [rad] + d_psi_rad_ = c_d_psi_rad_[0] * sin(O_rad) + c_d_psi_rad_[1] * sin(2 * Ld_rad) + c_d_psi_rad_[2] * sin(2 * O_rad) + + c_d_psi_rad_[3] * sin(2 * L_rad) + c_d_psi_rad_[4] * sin(ls_rad); // [rad] + d_psi_rad_ = d_psi_rad_ + c_d_psi_rad_[5] * sin(lm_rad) + c_d_psi_rad_[6] * sin(2 * Ld_rad + ls_rad) + c_d_psi_rad_[7] * sin(2 * L_rad + lm_rad) + + c_d_psi_rad_[8] * sin(2 * Ld_rad - ls_rad); // [rad] // Nutation in longitude - depsilon_rad_ = c_depsilon_rad_[0] * cos(O_rad) + c_depsilon_rad_[1] * cos(2 * Ld_rad) + c_depsilon_rad_[2] * cos(2 * O_rad) + - c_depsilon_rad_[3] * cos(2 * L_rad) + c_depsilon_rad_[4] * cos(ls_rad); // [rad] - depsilon_rad_ = depsilon_rad_ + c_depsilon_rad_[5] * cos(lm_rad) + c_depsilon_rad_[6] * cos(2 * Ld_rad + ls_rad) + - c_depsilon_rad_[7] * cos(2 * L_rad + lm_rad) + c_depsilon_rad_[8] * cos(2 * Ld_rad - ls_rad); // [rad] - - double epsi_mod_rad = epsi_rad_ + depsilon_rad_; - libra::Matrix<3, 3> X_epsi_1st = libra::rotx(epsi_rad_); - libra::Matrix<3, 3> Z_dpsi = libra::rotz(-dpsi_rad_); + d_epsilon_rad_ = c_d_epsilon_rad_[0] * cos(O_rad) + c_d_epsilon_rad_[1] * cos(2 * Ld_rad) + c_d_epsilon_rad_[2] * cos(2 * O_rad) + + c_d_epsilon_rad_[3] * cos(2 * L_rad) + c_d_epsilon_rad_[4] * cos(ls_rad); // [rad] + d_epsilon_rad_ = d_epsilon_rad_ + c_d_epsilon_rad_[5] * cos(lm_rad) + c_d_epsilon_rad_[6] * cos(2 * Ld_rad + ls_rad) + + c_d_epsilon_rad_[7] * cos(2 * L_rad + lm_rad) + c_d_epsilon_rad_[8] * cos(2 * Ld_rad - ls_rad); // [rad] + + double epsi_mod_rad = epsilon_rad_ + d_epsilon_rad_; + libra::Matrix<3, 3> X_epsi_1st = libra::rotx(epsilon_rad_); + libra::Matrix<3, 3> Z_dpsi = libra::rotz(-d_psi_rad_); libra::Matrix<3, 3> X_epsi_2nd = libra::rotx(-epsi_mod_rad); libra::Matrix<3, 3> N; diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 39fadec7c..c4e6126c3 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -10,8 +10,8 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ #define S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ -#include -#include +#include "library/logger/loggable.hpp" +#include "library/math/matrix.hpp" /** * @enum RotationMode @@ -50,13 +50,13 @@ class CelestialRotation { * @fn GetDCMJ2000toXCXF * @brief Return the DCM between J2000 inertial frame and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const libra::Matrix<3, 3> GetDCMJ2000toXCXF() const { return DCM_J2000toXCXF_; }; + inline const libra::Matrix<3, 3> GetDCMJ2000toXCXF() const { return dcm_j2000_to_xcxf_; }; /** * @fn GetDCMJ2000toXCXF * @brief Return the DCM between TEME (Inertial frame used in SGP4) and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const libra::Matrix<3, 3> GetDCMTEMEtoXCXF() const { return DCM_TEMEtoXCXF_; }; + inline const libra::Matrix<3, 3> GetDCMTEMEtoXCXF() const { return dcm_teme_to_xcxf_; }; private: /** @@ -73,34 +73,35 @@ class CelestialRotation { libra::Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession libra::Matrix<3, 3> PolarMotion(const double Xp, const double Yp); //!< Movement of the coordinate axes due to Polar Motion - double dpsi_rad_; //!< Nutation in obliquity [rad] - double depsilon_rad_; //!< Nutation in longitude [rad] - double epsi_rad_; //!< Mean obliquity of the ecliptic [rad] - libra::Matrix<3, 3> DCM_J2000toXCXF_; //!< Direction Cosine Matrix J2000 to XCXF(X-Centered X-Fixed) - libra::Matrix<3, 3> DCM_TEMEtoXCXF_; //!< Direction Cosine Matrix TEME to XCXF(X-Centered X-Fixed) - RotationMode rotation_mode_; //!< Designation of dynamics model - std::string planet_name_; //!< Designate which solar planet the instance should work as + double d_psi_rad_; //!< Nutation in obliquity [rad] + double d_epsilon_rad_; //!< Nutation in longitude [rad] + double epsilon_rad_; //!< Mean obliquity of the ecliptic [rad] + libra::Matrix<3, 3> dcm_j2000_to_xcxf_; //!< Direction Cosine Matrix J2000 to XCXF(X-Centered X-Fixed) + libra::Matrix<3, 3> dcm_teme_to_xcxf_; //!< Direction Cosine Matrix TEME to XCXF(X-Centered X-Fixed) + RotationMode rotation_mode_; //!< Designation of dynamics model + std::string planet_name_; //!< Designate which solar planet the instance should work as - // Definitions of coefficeints + // Definitions of coefficients // They are handling as constant values // TODO: Consider to read setting files for these coefficients // TODO: Consider other formats for other planets - double c_epsi_rad_[4]; //!< Coefficients to compute mean obliquity of the ecliptic - double c_lm_rad_[5]; //!< Coefficients to compute delauney angle (l=lm: Mean anomaly of the moon) - double c_ls_rad_[5]; //!< Coefficients to compute delauney angle (l'=ls: Mean anomaly of the sun) - double c_F_rad_[5]; //!< Coefficients to compute delauney angle (F: Mean longitude of the moon - mean longitude of ascending node of the moon) - double c_D_rad_[5]; //!< Coefficients to compute delauney angle (D: Elogation of the moon from the sun) - double c_O_rad_[5]; //!< Coefficients to compute delauney angle (Ω=O: Mean longitude of ascending node of the moon) - double c_depsilon_rad_[9]; //!< Coefficients to compute nutation angle (delta-epsilon) - double c_dpsi_rad_[9]; //!< Coefficients to compute nutation angle (delta-psi) - double c_zeta_rad_[3]; //!< Coefficients to compute precession angle (zeta) - double c_theta_rad_[3]; //!< Coefficients to compute precession angle (theta) - double c_z_rad_[2]; //!< Coefficients to compute precession angle (z) + double c_epsilon_rad_[4]; //!< Coefficients to compute mean obliquity of the ecliptic + double c_lm_rad_[5]; //!< Coefficients to compute delauney angle (l=lm: Mean anomaly of the moon) + double c_ls_rad_[5]; //!< Coefficients to compute delauney angle (l'=ls: Mean anomaly of the sun) + double c_f_rad_[5]; //!< Coefficients to compute delauney angle (F: Mean longitude of the moon - mean longitude of ascending node of the moon) + double c_d_rad_[5]; //!< Coefficients to compute delauney angle (D: Elogation of the moon from the sun) + double c_o_rad_[5]; //!< Coefficients to compute delauney angle (Ω=O: Mean longitude of ascending node of the moon) + double c_d_epsilon_rad_[9]; //!< Coefficients to compute nutation angle (delta-epsilon) + double c_d_psi_rad_[9]; //!< Coefficients to compute nutation angle (delta-psi) + double c_zeta_rad_[3]; //!< Coefficients to compute precession angle (zeta) + double c_theta_rad_[3]; //!< Coefficients to compute precession angle (theta) + double c_z_rad_[2]; //!< Coefficients to compute precession angle (z) - const double dtUT1UTC_ = 32.184; //!< Time difference b/w UT1 and UTC [sec] - const double kSec2Day = 1 / (24.0 * 60.0 * 60.0); //!< Conversion constant from sec to day - const double kJulianDateJ2000 = 2451545.0; //!< Julian date of J2000 [day] - const double kDayJulianCentury = 36525; //!< Conversion constant from Julian century to day [day/century] + // TODO: Move to general constant values + const double kDtUt1Utc_ = 32.184; //!< Time difference b/w UT1 and UTC [sec] + const double kSec2Day_ = 1.0 / (24.0 * 60.0 * 60.0); //!< Conversion constant from sec to day + const double kJulianDateJ2000_ = 2451545.0; //!< Julian date of J2000 [day] + const double kDayJulianCentury_ = 36525.0; //!< Conversion constant from Julian century to day [day/century] }; #endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ From fc136060f68ccc2d667af51184a738575ed55fa9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:30:39 +0100 Subject: [PATCH 0500/1086] Fix private function name --- src/environment/global/celestial_rotation.cpp | 6 ++-- src/environment/global/celestial_rotation.hpp | 28 +++++++++---------- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index 1e3474832..fcf5534be 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -23,14 +23,14 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std unitalize(dcm_j2000_to_xcxf_); dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; if (center_obj == "EARTH") { - Init_CelestialRotation_As_Earth(rotation_mode, center_obj); + InitCelestialRotationAsEarth(rotation_mode, center_obj); } } // Initialize the class CelestialRotation instance as Earth -void CelestialRotation::Init_CelestialRotation_As_Earth(const RotationMode rotation_mode, const std::string center_obj) { +void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "EARTH"; - if (center_obj == planet_name_) { + if (center_body_name == planet_name_) { if (rotation_mode == Simple) { rotation_mode_ = Simple; // For Simple mode, we don't need initialization of the coefficients diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index c4e6126c3..789610470 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -59,20 +59,6 @@ class CelestialRotation { inline const libra::Matrix<3, 3> GetDCMTEMEtoXCXF() const { return dcm_teme_to_xcxf_; }; private: - /** - * @fn Init_CelestialRotation_As_Earth - * @brief Initialize CelestialRotation as earth rotation - * @note TODO: Make functions for other planets? - * @param [in] rotation_mode: Rotation mode - * @param [in] center_obj: Name of center body - */ - void Init_CelestialRotation_As_Earth(const RotationMode rotation_mode, const std::string center_obj); - - libra::Matrix<3, 3> AxialRotation(const double GAST_rad); //!< Movement of the coordinate axes due to rotation around the rotation axis - libra::Matrix<3, 3> Nutation(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Nutation - libra::Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession - libra::Matrix<3, 3> PolarMotion(const double Xp, const double Yp); //!< Movement of the coordinate axes due to Polar Motion - double d_psi_rad_; //!< Nutation in obliquity [rad] double d_epsilon_rad_; //!< Nutation in longitude [rad] double epsilon_rad_; //!< Mean obliquity of the ecliptic [rad] @@ -102,6 +88,20 @@ class CelestialRotation { const double kSec2Day_ = 1.0 / (24.0 * 60.0 * 60.0); //!< Conversion constant from sec to day const double kJulianDateJ2000_ = 2451545.0; //!< Julian date of J2000 [day] const double kDayJulianCentury_ = 36525.0; //!< Conversion constant from Julian century to day [day/century] + + /** + * @fn InitCelestialRotationAsEarth + * @brief Initialize CelestialRotation as earth rotation + * @note TODO: Make functions for other planets? + * @param [in] rotation_mode: Rotation mode + * @param [in] center_body_name: Name of center body + */ + void InitCelestialRotationAsEarth(const RotationMode rotation_mode, const std::string center_body_name); + + libra::Matrix<3, 3> AxialRotation(const double GAST_rad); //!< Movement of the coordinate axes due to rotation around the rotation axis + libra::Matrix<3, 3> Nutation(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Nutation + libra::Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession + libra::Matrix<3, 3> PolarMotion(const double Xp, const double Yp); //!< Movement of the coordinate axes due to Polar Motion }; #endif // S2E_ENVIRONMENT_GLOBAL_CELESTIAL_ROTATION_HPP_ From 12c9556a8c0af73e957e46d636cda26193d3db70 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:34:14 +0100 Subject: [PATCH 0501/1086] Fix function argument name --- src/environment/global/celestial_rotation.cpp | 6 +++--- src/environment/global/celestial_rotation.hpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index fcf5534be..a7df118cb 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -17,13 +17,13 @@ #include "library/math/constants.hpp" // Default constructor -CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_obj) { +CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "Anonymous"; rotation_mode_ = Idle; unitalize(dcm_j2000_to_xcxf_); dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; - if (center_obj == "EARTH") { - InitCelestialRotationAsEarth(rotation_mode, center_obj); + if (center_body_name == "EARTH") { + InitCelestialRotationAsEarth(rotation_mode, center_body_name); } } diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index 789610470..ebb204ae5 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -35,9 +35,9 @@ class CelestialRotation { * @fn CelestialRotation * @brief Constructor * @param [in] rotation_mode: Designation of rotation model - * @param [in] center_obj: Center object of inertial frame + * @param [in] center_body_name: Center object of inertial frame */ - CelestialRotation(const RotationMode rotation_mode, const std::string center_obj); + CelestialRotation(const RotationMode rotation_mode, const std::string center_body_name); /** * @fn Update From a8b44b03389ebc0f5705ba4cdece99295eff2cb4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:37:14 +0100 Subject: [PATCH 0502/1086] Fix public function name --- src/disturbances/geopotential.cpp | 2 +- src/dynamics/orbit/orbit.cpp | 2 +- src/environment/global/celestial_rotation.hpp | 10 ++++++---- src/simulation/ground_station/ground_station.cpp | 2 +- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index b28f8cc01..0b2132df7 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -78,7 +78,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif - Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDCMJ2000toXCXF(); + Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDcmJ2000ToXcxf(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index dec0509c7..8f4f93ae6 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -28,7 +28,7 @@ Quaternion Orbit::CalcQuaternionI2LVLH() const { } void Orbit::TransEciToEcef(void) { - Matrix<3, 3> dcm_i_to_xcxf = celes_info_->GetEarthRotation().GetDCMJ2000toXCXF(); + Matrix<3, 3> dcm_i_to_xcxf = celes_info_->GetEarthRotation().GetDcmJ2000ToXcxf(); sat_position_ecef_ = dcm_i_to_xcxf * sat_position_i_; // convert velocity vector in ECI to the vector in ECEF diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index ebb204ae5..d5bc76b95 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -47,16 +47,16 @@ class CelestialRotation { void Update(const double JulianDate); /** - * @fn GetDCMJ2000toXCXF + * @fn GetDcmJ2000ToXcxf * @brief Return the DCM between J2000 inertial frame and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const libra::Matrix<3, 3> GetDCMJ2000toXCXF() const { return dcm_j2000_to_xcxf_; }; + inline const libra::Matrix<3, 3> GetDcmJ2000ToXcxf() const { return dcm_j2000_to_xcxf_; }; /** - * @fn GetDCMJ2000toXCXF + * @fn GetDcmJ2000ToXcxf * @brief Return the DCM between TEME (Inertial frame used in SGP4) and the frame of fixed to the target object X (X-Centered X-Fixed) */ - inline const libra::Matrix<3, 3> GetDCMTEMEtoXCXF() const { return dcm_teme_to_xcxf_; }; + inline const libra::Matrix<3, 3> GetDcmTemeToXcxf() const { return dcm_teme_to_xcxf_; }; private: double d_psi_rad_; //!< Nutation in obliquity [rad] @@ -98,6 +98,8 @@ class CelestialRotation { */ void InitCelestialRotationAsEarth(const RotationMode rotation_mode, const std::string center_body_name); + // TODO: Add doxygen comments for the private functions and fix argument name + libra::Matrix<3, 3> AxialRotation(const double GAST_rad); //!< Movement of the coordinate axes due to rotation around the rotation axis libra::Matrix<3, 3> Nutation(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Nutation libra::Matrix<3, 3> Precession(const double (&tTT_century)[4]); //!< Movement of the coordinate axes due to Precession diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 83a5ece75..d536116f6 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -45,7 +45,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { void GroundStation::LogSetup(Logger& logger) { logger.AddLoggable(this); } void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft) { - Matrix<3, 3> dcm_ecef2eci = transpose(celes_rotation.GetDCMJ2000toXCXF()); + Matrix<3, 3> dcm_ecef2eci = transpose(celes_rotation.GetDcmJ2000ToXcxf()); gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; is_visible_[spacecraft.GetSatID()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetSatPosition_ecef()); From a60a3ad20f24375eef562f67b91ca067fa3f7561 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:39:44 +0100 Subject: [PATCH 0503/1086] Delete unused public variables --- src/environment/global/clock_generator.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 91714fe67..008e7f8b7 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -52,8 +52,6 @@ class ClockGenerator { */ inline void ClearTimerCount(void) { timer_count_ = 0; } - const int IntervalMillisecond = 1; //!< Clock period [ms]. (Currenly, this is not used. TODO: Delete this.) - private: std::vector components_; //!< Component list fot tick int timer_count_; //!< Timer count TODO: consider size, unsigned From cf7dd574af21431f5a0f057e2d18651be8cec0e1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:42:04 +0100 Subject: [PATCH 0504/1086] Fix include --- src/environment/global/global_environment.cpp | 3 +-- src/environment/global/global_environment.hpp | 5 ++--- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index c93c336c9..fc9ceb3bd 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -5,10 +5,9 @@ #include "global_environment.hpp" -#include - #include "initialize_global_environment.hpp" #include "initialize_gnss_satellites.hpp" +#include "library/initialize/initialize_file_access.hpp" GlobalEnvironment::GlobalEnvironment(SimulationConfig* sim_config) { Initialize(sim_config); } diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 2ae00f1db..fc91178c9 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -6,12 +6,11 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ -#include -#include - #include "celestial_information.hpp" #include "gnss_satellites.hpp" #include "hipparcos_catalogue.hpp" +#include "library/logger/logger.hpp" +#include "simulation/simulation_configuration.hpp" #include "simulation_time.hpp" /** From f54b8724a8a2b630ca366d5b860afc07d01fe1c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:45:34 +0100 Subject: [PATCH 0505/1086] Fix private member name --- src/environment/global/global_environment.cpp | 38 +++++++++---------- src/environment/global/global_environment.hpp | 22 +++++------ 2 files changed, 30 insertions(+), 30 deletions(-) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index fc9ceb3bd..651256a87 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -9,40 +9,40 @@ #include "initialize_gnss_satellites.hpp" #include "library/initialize/initialize_file_access.hpp" -GlobalEnvironment::GlobalEnvironment(SimulationConfig* sim_config) { Initialize(sim_config); } +GlobalEnvironment::GlobalEnvironment(SimulationConfig* simulation_configuration) { Initialize(simulation_configuration); } GlobalEnvironment::~GlobalEnvironment() { - delete sim_time_; - delete celes_info_; - delete hipp_; + delete simulation_time_; + delete celestial_information_; + delete hipparcos_catalogue_; delete gnss_satellites_; } -void GlobalEnvironment::Initialize(SimulationConfig* sim_config) { +void GlobalEnvironment::Initialize(SimulationConfig* simulation_configuration) { // Get ini file path - IniAccess iniAccess = IniAccess(sim_config->ini_base_fname_); - std::string sim_time_ini_path = sim_config->ini_base_fname_; + IniAccess iniAccess = IniAccess(simulation_configuration->ini_base_fname_); + std::string simulation_time_ini_path = simulation_configuration->ini_base_fname_; // Initialize - sim_time_ = InitSimTime(sim_time_ini_path); - celes_info_ = InitCelesInfo(sim_config->ini_base_fname_); - hipp_ = InitHipCatalogue(sim_config->ini_base_fname_); - gnss_satellites_ = InitGnssSatellites(sim_config->gnss_file_); + simulation_time_ = InitSimTime(simulation_time_ini_path); + celestial_information_ = InitCelesInfo(simulation_configuration->ini_base_fname_); + hipparcos_catalogue_ = InitHipCatalogue(simulation_configuration->ini_base_fname_); + gnss_satellites_ = InitGnssSatellites(simulation_configuration->gnss_file_); // Calc initial value - celes_info_->UpdateAllObjectsInfo(sim_time_->GetCurrentJd()); - gnss_satellites_->SetUp(sim_time_); + celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentJd()); + gnss_satellites_->SetUp(simulation_time_); } void GlobalEnvironment::Update() { - sim_time_->UpdateTime(); - celes_info_->UpdateAllObjectsInfo(sim_time_->GetCurrentJd()); - gnss_satellites_->Update(sim_time_); + simulation_time_->UpdateTime(); + celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentJd()); + gnss_satellites_->Update(simulation_time_); } void GlobalEnvironment::LogSetup(Logger& logger) { - logger.AddLoggable(sim_time_); - logger.AddLoggable(celes_info_); + logger.AddLoggable(simulation_time_); + logger.AddLoggable(celestial_information_); } -void GlobalEnvironment::Reset(void) { sim_time_->ResetClock(); } +void GlobalEnvironment::Reset(void) { simulation_time_->ResetClock(); } diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index fc91178c9..480a2e6fb 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -22,9 +22,9 @@ class GlobalEnvironment { /** * @fn ~GlobalEnvironment * @brief Constructor - * @param [in] sim_config: Simulation configuration + * @param [in] simulation_configuration: Simulation configuration */ - GlobalEnvironment(SimulationConfig* sim_config); + GlobalEnvironment(SimulationConfig* simulation_configuration); /** * @fn ~GlobalEnvironment * @brief Destructor @@ -34,9 +34,9 @@ class GlobalEnvironment { /** * @fn Initialize * @brief Initialize all global environment members - * @param [in] sim_config: Simulation configuration + * @param [in] simulation_configuration: Simulation configuration */ - void Initialize(SimulationConfig* sim_config); + void Initialize(SimulationConfig* simulation_configuration); /** * @fn Update * @brief Update states of all global environment @@ -58,17 +58,17 @@ class GlobalEnvironment { * @fn GetSimTime * @brief Return SimTime */ - inline const SimTime& GetSimTime() const { return *sim_time_; } + inline const SimTime& GetSimTime() const { return *simulation_time_; } /** * @fn GetCelesInfo * @brief Return CelestialInformation */ - inline const CelestialInformation& GetCelesInfo() const { return *celes_info_; } + inline const CelestialInformation& GetCelesInfo() const { return *celestial_information_; } /** * @fn GetHippCatalog * @brief Return HipparcosCatalogue */ - inline const HipparcosCatalogue& GetHippCatalog() const { return *hipp_; } + inline const HipparcosCatalogue& GetHippCatalog() const { return *hipparcos_catalogue_; } /** * @fn GetGnssSatellites * @brief Return GnssSatellites @@ -76,10 +76,10 @@ class GlobalEnvironment { inline const GnssSatellites& GetGnssSatellites() const { return *gnss_satellites_; } private: - SimTime* sim_time_; //!< Simulation time - CelestialInformation* celes_info_; //!< Celestial bodies information - HipparcosCatalogue* hipp_; //!< Hipparcos catalogue - GnssSatellites* gnss_satellites_; //!< GNSS satellites + SimTime* simulation_time_; //!< Simulation time + CelestialInformation* celestial_information_; //!< Celestial bodies information + HipparcosCatalogue* hipparcos_catalogue_; //!< Hipparcos catalogue + GnssSatellites* gnss_satellites_; //!< GNSS satellites }; #endif // S2E_ENVIRONMENT_GLOBAL_GLOBAL_ENVIRONMENT_HPP_ From 9dc7a75eb54f7559a99713536370e17e70aeb04d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:48:21 +0100 Subject: [PATCH 0506/1086] Fix public function name --- src/disturbances/disturbances.cpp | 6 +++--- src/environment/global/global_environment.hpp | 4 ++-- src/environment/local/local_environment.cpp | 4 ++-- src/simulation/case/sample_case.cpp | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 85fe4ecea..58dbe7a84 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -66,8 +66,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const IniAccess ini_access = IniAccess(sim_config->sat_file_[sat_id]); initialize_file_name_ = ini_access.ReadString("SETTING_FILES", "disturbance_file"); - GravityGradient* gg_dist = - new GravityGradient(InitGravityGradient(initialize_file_name_, global_environment->GetCelesInfo().GetCenterBodyGravityConstant_m3_s2())); + GravityGradient* gg_dist = new GravityGradient( + InitGravityGradient(initialize_file_name_, global_environment->GetCelestialInformation().GetCenterBodyGravityConstant_m3_s2())); disturbances_list_.push_back(gg_dist); SolarRadiation* srp_dist = new SolarRadiation( @@ -77,7 +77,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->ini_base_fname_)); acceleration_disturbances_list_.push_back(third_body_gravity); - if (global_environment->GetCelesInfo().GetCenterBodyName() != "EARTH") return; + if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) AirDrag* air_dist = new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(air_dist); diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 480a2e6fb..573c45b8e 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -63,12 +63,12 @@ class GlobalEnvironment { * @fn GetCelesInfo * @brief Return CelestialInformation */ - inline const CelestialInformation& GetCelesInfo() const { return *celestial_information_; } + inline const CelestialInformation& GetCelestialInformation() const { return *celestial_information_; } /** * @fn GetHippCatalog * @brief Return HipparcosCatalogue */ - inline const HipparcosCatalogue& GetHippCatalog() const { return *hipparcos_catalogue_; } + inline const HipparcosCatalogue& GetHipparcosCatalog() const { return *hipparcos_catalogue_; } /** * @fn GetGnssSatellites * @brief Return GnssSatellites diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 3f5240cc5..0ea0ee464 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -30,10 +30,10 @@ void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvi // Initialize mag_ = new MagEnvironment(InitMagEnvironment(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); - celes_info_ = new LocalCelestialInformation(&(glo_env->GetCelesInfo())); + celes_info_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); srp_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celes_info_)); // Force to disable when the center body is not the Earth - if (glo_env->GetCelesInfo().GetCenterBodyName() != "EARTH") { + if (glo_env->GetCelestialInformation().GetCenterBodyName() != "EARTH") { mag_->IsCalcEnabled = false; atmosphere_->IsCalcEnabled = false; } diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 687d4ba8d..745439434 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -48,7 +48,7 @@ void SampleCase::Main() { // Spacecraft Update sample_sat_->Update(&(glo_env_->GetSimTime())); // Ground Station Update - sample_gs_->Update(glo_env_->GetCelesInfo().GetEarthRotation(), *sample_sat_); + sample_gs_->Update(glo_env_->GetCelestialInformation().GetEarthRotation(), *sample_sat_); // Debug output if (glo_env_->GetSimTime().GetState().disp_output) { From ac2a491bd2f702f875b2381aecee1e310668f86f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:49:47 +0100 Subject: [PATCH 0507/1086] Fix public function name --- src/environment/global/global_environment.hpp | 2 +- src/simulation/case/sample_case.cpp | 14 +++++++------- .../sample_spacecraft/sample_components.cpp | 16 ++++++++-------- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 573c45b8e..bc9b5939b 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -58,7 +58,7 @@ class GlobalEnvironment { * @fn GetSimTime * @brief Return SimTime */ - inline const SimTime& GetSimTime() const { return *simulation_time_; } + inline const SimTime& GetSimulationTime() const { return *simulation_time_; } /** * @fn GetCelesInfo * @brief Return CelestialInformation diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 745439434..cdf879941 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -32,27 +32,27 @@ void SampleCase::Initialize() { // Start the simulation cout << "\nSimulationDateTime \n"; - glo_env_->GetSimTime().PrintStartDateTime(); + glo_env_->GetSimulationTime().PrintStartDateTime(); } void SampleCase::Main() { glo_env_->Reset(); // for MonteCarlo Sim - while (!glo_env_->GetSimTime().GetState().finish) { + while (!glo_env_->GetSimulationTime().GetState().finish) { // Logging - if (glo_env_->GetSimTime().GetState().log_output) { + if (glo_env_->GetSimulationTime().GetState().log_output) { sim_config_.main_logger_->WriteValues(); } // Global Environment Update glo_env_->Update(); // Spacecraft Update - sample_sat_->Update(&(glo_env_->GetSimTime())); + sample_sat_->Update(&(glo_env_->GetSimulationTime())); // Ground Station Update sample_gs_->Update(glo_env_->GetCelestialInformation().GetEarthRotation(), *sample_sat_); // Debug output - if (glo_env_->GetSimTime().GetState().disp_output) { - cout << "Progresss: " << glo_env_->GetSimTime().GetProgressionRate() << "%\r"; + if (glo_env_->GetSimulationTime().GetState().disp_output) { + cout << "Progresss: " << glo_env_->GetSimulationTime().GetProgressionRate() << "%\r"; } } } @@ -78,7 +78,7 @@ string SampleCase::GetLogValue() const { // auto omega_b = sample_sat->dynamics_->GetAttitude().GetOmega_b(); // Need to match the contents of log with header setting above - str_tmp += WriteScalar(glo_env_->GetSimTime().GetElapsedSec()); + str_tmp += WriteScalar(glo_env_->GetSimulationTime().GetElapsedSec()); // str_tmp += WriteVector(pos_i, 16); // str_tmp += WriteVector(vel_i, 10); // str_tmp += WriteQuaternion(quat_i2b); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index b3db1f800..571844570 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -27,18 +27,18 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Gyro std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), dynamics_)); + gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), dynamics_)); // MagSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - mag_sensor_ = - new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); + mag_sensor_ = new MagSensor( + InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), &(local_env_->GetMag()))); // STT ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - stt_ = new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), dynamics_, local_env_)); + stt_ = new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), dynamics_, local_env_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); @@ -49,19 +49,19 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); config_->main_logger_->CopyFileToLogDir(ini_path); gnss_ = new GNSSReceiver( - InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimTime()))); + InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); // MagTorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_torquer_ = new MagTorquer( - InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimTime().GetCompoStepSec(), &(local_env_->GetMag()))); + InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), &(local_env_->GetMag()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - rw_ = new RWModel( - InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), glo_env_->GetSimTime().GetCompoStepSec())); + rw_ = new RWModel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), + glo_env_->GetSimulationTime().GetCompoStepSec())); // Torque Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 9802170e3..04801e39d 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -32,7 +32,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen clock_gen_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimTime()), &(local_env_->GetCelesInfo()), sat_id, structure_); + dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelesInfo()), sat_id, structure_); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); @@ -44,7 +44,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen clock_gen_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimTime()), &(local_env_->GetCelesInfo()), sat_id, structure_, rel_info); + dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelesInfo()), sat_id, structure_, rel_info); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); From 135d107bd8c265273e954fdfd6a7399c646691c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:52:46 +0100 Subject: [PATCH 0508/1086] Fix include files --- src/environment/global/gnss_satellites.cpp | 14 +++++++------- src/environment/global/gnss_satellites.hpp | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index ef9048769..5049b1120 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -5,18 +5,18 @@ #include "gnss_satellites.hpp" -#include //for jday() -#include //for gstime() - #include -#include #include -#include -#include -#include #include #include +#include "environment/global/physical_constants.hpp" +#include "library/external/sgp4/sgp4ext.h" //for jday() +#include "library/external/sgp4/sgp4unit.h" //for gstime() +#include "library/logger/log_utility.hpp" +#include "library/math/constants.hpp" +#include "library/utilities/macros.hpp" + const double nan99 = 999999.999999; const int gps_sat_num_ = 32; //!< Number of GPS satellites diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 31f840ebf..2fd323e8c 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -10,11 +10,11 @@ #include #include #include -#include -#include #include #include +#include "library/logger/loggable.hpp" +#include "library/math/vector.hpp" #include "simulation_time.hpp" extern const double nan99; //!< Not at Number TODO: Should be moved to another place From 1754b310f7ae67d506bd7d9cf4f3af5762ccdc71 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:55:08 +0100 Subject: [PATCH 0509/1086] Remove using --- .../global/hipparcos_catalogue.cpp | 27 +++++++++---------- .../global/hipparcos_catalogue.hpp | 7 ++--- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index b0f444d8e..59eeb6ee4 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -7,36 +7,35 @@ #include #include #include -#include #include #include #include -using namespace std; +#include "library/math/constants.hpp" -HipparcosCatalogue::HipparcosCatalogue(double max_magnitude, string catalogue_path) +HipparcosCatalogue::HipparcosCatalogue(double max_magnitude, std::string catalogue_path) : max_magnitude_(max_magnitude), catalogue_path_(catalogue_path) {} HipparcosCatalogue::~HipparcosCatalogue() {} -bool HipparcosCatalogue::ReadContents(const string& filename, const char delimiter = ',') { +bool HipparcosCatalogue::ReadContents(const std::string& filename, const char delimiter = ',') { if (!IsCalcEnabled) return false; - ifstream ifs(filename); + std::ifstream ifs(filename); if (!ifs.is_open()) { - cerr << "file open error(hip_main.csv)"; + std::cerr << "file open error(hip_main.csv)"; return false; } - string title; + std::string title; ifs >> title; // Skip title while (!ifs.eof()) { HipData hipdata; - string line; + std::string line; ifs >> line; - replace(line.begin(), line.end(), delimiter, ' '); // Convert delimiter as space for stringstream - istringstream streamline(line); + std::replace(line.begin(), line.end(), delimiter, ' '); // Convert delimiter as space for stringstream + std::istringstream streamline(line); streamline >> hipdata.hip_num >> hipdata.vmag >> hipdata.ra >> hipdata.de; @@ -71,14 +70,14 @@ libra::Vector<3> HipparcosCatalogue::GetStarDir_b(int rank, Quaternion q_i2b) co return position_b; } -string HipparcosCatalogue::GetLogHeader() const { - string str_tmp = ""; +std::string HipparcosCatalogue::GetLogHeader() const { + std::string str_tmp = ""; return str_tmp; } -string HipparcosCatalogue::GetLogValue() const { - string str_tmp = ""; +std::string HipparcosCatalogue::GetLogValue() const { + std::string str_tmp = ""; return str_tmp; } diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index b57c6c3c1..9aa3da74f 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -6,11 +6,12 @@ #ifndef S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ #define S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ -#include -#include -#include #include +#include "library/logger/loggable.hpp" +#include "library/math/quaternion.hpp" +#include "library/math/vector.hpp" + /** *@struct HipData *@brief Hipparcos catalogue data From 9e2f1e193f28e48a60fa14091ac88b0916ef030e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 10:58:26 +0100 Subject: [PATCH 0510/1086] Fix private member name --- src/environment/global/hipparcos_catalogue.cpp | 2 +- src/environment/global/hipparcos_catalogue.hpp | 18 +++++++++--------- .../global/initialize_global_environment.cpp | 12 ++++++------ 3 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index 59eeb6ee4..d55b700f0 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -42,7 +42,7 @@ bool HipparcosCatalogue::ReadContents(const std::string& filename, const char de if (hipdata.vmag > max_magnitude_) { return true; } // Don't read stars darker than max_magnitude - hip_catalogue.push_back(hipdata); + hipparcos_catalogue_.push_back(hipdata); } return true; diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 9aa3da74f..36f65ab43 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -19,7 +19,7 @@ struct HipData { int hip_num; //!< Hipparcos number double vmag; //!< Visible magnitude - double ra; //!< Right ascention [rad] + double ra; //!< Right ascension [rad] double de; //!< Declination [rad] }; @@ -53,31 +53,31 @@ class HipparcosCatalogue : public ILoggable { *@fn GetCatalogueSize *@brief Return read catalogue size */ - int GetCatalogueSize() const { return hip_catalogue.size(); } + int GetCatalogueSize() const { return hipparcos_catalogue_.size(); } /** *@fn GetHipID *@brief Return Hipparcos ID of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - int GetHipID(int rank) const { return hip_catalogue[rank].hip_num; } + int GetHipID(int rank) const { return hipparcos_catalogue_[rank].hip_num; } /** *@fn GetVmag *@brief Return magnitude in visible wave length of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetVmag(int rank) const { return hip_catalogue[rank].vmag; } + double GetVmag(int rank) const { return hipparcos_catalogue_[rank].vmag; } /** *@fn GetRA *@brief Return right ascension of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetRA(int rank) const { return hip_catalogue[rank].ra; } + double GetRA(int rank) const { return hipparcos_catalogue_[rank].ra; } /** *@fn GetDE *@brief Return declination of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetDE(int rank) const { return hip_catalogue[rank].de; } + double GetDE(int rank) const { return hipparcos_catalogue_[rank].de; } /** *@fn GetStarDir_i *@brief Return direction vector of a star in the inertial frame @@ -107,9 +107,9 @@ class HipparcosCatalogue : public ILoggable { bool IsCalcEnabled = true; //!< Calculation enable flag private: - std::vector hip_catalogue; //!< Data base of the read Hipparcos catalogue - double max_magnitude_; //!< Maximum magnitude in the data base - std::string catalogue_path_; //!< Path to Hipparcos catalog file + std::vector hipparcos_catalogue_; //!< Data base of the read Hipparcos catalogue + double max_magnitude_; //!< Maximum magnitude in the data base + std::string catalogue_path_; //!< Path to Hipparcos catalog file }; #endif // S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index d59d1263e..b3b2c7eba 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -52,13 +52,13 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name) { std::string catalogue_path = ini_file.ReadString(section, "catalogue_file_path"); double max_magnitude = ini_file.ReadDouble(section, "max_magnitude"); - HipparcosCatalogue* hip_catalogue; - hip_catalogue = new HipparcosCatalogue(max_magnitude, catalogue_path); - hip_catalogue->IsCalcEnabled = ini_file.ReadEnable(section, CALC_LABEL); - hip_catalogue->IsLogEnabled = ini_file.ReadEnable(section, LOG_LABEL); - hip_catalogue->ReadContents(catalogue_path, ','); + HipparcosCatalogue* hipparcos_catalogue_; + hipparcos_catalogue_ = new HipparcosCatalogue(max_magnitude, catalogue_path); + hipparcos_catalogue_->IsCalcEnabled = ini_file.ReadEnable(section, CALC_LABEL); + hipparcos_catalogue_->IsLogEnabled = ini_file.ReadEnable(section, LOG_LABEL); + hipparcos_catalogue_->ReadContents(catalogue_path, ','); - return hip_catalogue; + return hipparcos_catalogue_; } CelestialInformation* InitCelesInfo(std::string file_name) { From b2966c97474227b0feb34751c7811ac96e3bef2b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:04:55 +0100 Subject: [PATCH 0511/1086] Fix public function name --- src/components/real/mission/telescope.cpp | 6 +++--- src/environment/global/hipparcos_catalogue.cpp | 7 ++++--- src/environment/global/hipparcos_catalogue.hpp | 12 ++++++------ 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index d6173563d..c268ebffa 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -109,7 +109,7 @@ void Telescope::ObserveStars() { int count = 0; // Counter for while loop while (star_in_sight.size() < num_of_logged_stars_) { - Vector<3> target_b = hipp_->GetStarDir_b(count, q_i2b); + Vector<3> target_b = hipp_->GetStarDirection_b(count, q_i2b); Vector<3> target_c = q_b2c_.frame_conv(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame @@ -117,8 +117,8 @@ void Telescope::ObserveStars() { if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { Star star; - star.hipdata.hip_num = hipp_->GetHipID(count); - star.hipdata.vmag = hipp_->GetVmag(count); + star.hipdata.hip_num = hipp_->GetHipparcosId(count); + star.hipdata.vmag = hipp_->GetVisibleMagnitude(count); star.hipdata.ra = hipp_->GetRA(count); star.hipdata.de = hipp_->GetDE(count); star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index d55b700f0..64476cadd 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -48,8 +48,9 @@ bool HipparcosCatalogue::ReadContents(const std::string& filename, const char de return true; } -libra::Vector<3> HipparcosCatalogue::GetStarDir_i(int rank) const { +libra::Vector<3> HipparcosCatalogue::GetStarDirection_i(int rank) const { libra::Vector<3> position; + // TODO: Check unit of ra and de double ra = GetRA(rank) * libra::pi / 180; double de = GetDE(rank) * libra::pi / 180; @@ -60,11 +61,11 @@ libra::Vector<3> HipparcosCatalogue::GetStarDir_i(int rank) const { return position; } -libra::Vector<3> HipparcosCatalogue::GetStarDir_b(int rank, Quaternion q_i2b) const { +libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, Quaternion q_i2b) const { libra::Vector<3> position_i; libra::Vector<3> position_b; - position_i = GetStarDir_i(rank); + position_i = GetStarDirection_i(rank); position_b = q_i2b.frame_conv(position_i); return position_b; diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 36f65ab43..a94a329b8 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -55,17 +55,17 @@ class HipparcosCatalogue : public ILoggable { */ int GetCatalogueSize() const { return hipparcos_catalogue_.size(); } /** - *@fn GetHipID + *@fn GetHipparcosId *@brief Return Hipparcos ID of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - int GetHipID(int rank) const { return hipparcos_catalogue_[rank].hip_num; } + int GetHipparcosId(int rank) const { return hipparcos_catalogue_[rank].hip_num; } /** - *@fn GetVmag + *@fn GetVisibleMagnitude *@brief Return magnitude in visible wave length of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetVmag(int rank) const { return hipparcos_catalogue_[rank].vmag; } + double GetVisibleMagnitude(int rank) const { return hipparcos_catalogue_[rank].vmag; } /** *@fn GetRA *@brief Return right ascension of a star @@ -83,14 +83,14 @@ class HipparcosCatalogue : public ILoggable { *@brief Return direction vector of a star in the inertial frame *@param [in] rank: Rank of star magnitude in read catalogue */ - libra::Vector<3> GetStarDir_i(int rank) const; + libra::Vector<3> GetStarDirection_i(int rank) const; /** *@fn GetStarDir_b *@brief Return direction vector of a star in the body-fixed frame *@param [in] rank: Rank of star magnitude in read catalogue *@param [in] rank: Quaternion from the inertial frame to the body-fixed frame */ - libra::Vector<3> GetStarDir_b(int rank, Quaternion q_i2b) const; + libra::Vector<3> GetStarDirection_b(int rank, Quaternion q_i2b) const; // Override ILoggable /** From 924d9ac7606bf2662cb41f08db67f5d16b7a094b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:06:46 +0100 Subject: [PATCH 0512/1086] Fix public file name --- src/environment/global/global_environment.cpp | 6 +++--- src/environment/global/initialize_global_environment.cpp | 6 +++--- src/environment/global/initialize_global_environment.hpp | 6 +++--- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 651256a87..715dc1f2c 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -24,9 +24,9 @@ void GlobalEnvironment::Initialize(SimulationConfig* simulation_configuration) { std::string simulation_time_ini_path = simulation_configuration->ini_base_fname_; // Initialize - simulation_time_ = InitSimTime(simulation_time_ini_path); - celestial_information_ = InitCelesInfo(simulation_configuration->ini_base_fname_); - hipparcos_catalogue_ = InitHipCatalogue(simulation_configuration->ini_base_fname_); + simulation_time_ = InitSimulationTime(simulation_time_ini_path); + celestial_information_ = InitCelestialInformation(simulation_configuration->ini_base_fname_); + hipparcos_catalogue_ = InitHipparcosCatalogue(simulation_configuration->ini_base_fname_); gnss_satellites_ = InitGnssSatellites(simulation_configuration->gnss_file_); // Calc initial value diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index b3b2c7eba..c38a947de 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -13,7 +13,7 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -SimTime* InitSimTime(std::string file_name) { +SimTime* InitSimulationTime(std::string file_name) { IniAccess ini_file(file_name); const char* section = "TIME"; @@ -45,7 +45,7 @@ SimTime* InitSimTime(std::string file_name) { return simTime; } -HipparcosCatalogue* InitHipCatalogue(std::string file_name) { +HipparcosCatalogue* InitHipparcosCatalogue(std::string file_name) { IniAccess ini_file(file_name); const char* section = "HIPPARCOS_CATALOGUE"; @@ -61,7 +61,7 @@ HipparcosCatalogue* InitHipCatalogue(std::string file_name) { return hipparcos_catalogue_; } -CelestialInformation* InitCelesInfo(std::string file_name) { +CelestialInformation* InitCelestialInformation(std::string file_name) { IniAccess ini_file(file_name); const char* section = "CELESTIAL_INFORMATION"; const char* furnsh_section = "CSPICE_KERNELS"; diff --git a/src/environment/global/initialize_global_environment.hpp b/src/environment/global/initialize_global_environment.hpp index 43446a516..657a081ea 100644 --- a/src/environment/global/initialize_global_environment.hpp +++ b/src/environment/global/initialize_global_environment.hpp @@ -15,20 +15,20 @@ *@brief Initialize function for SimTime class *@param [in] file_name: Path to the initialize function */ -SimTime* InitSimTime(std::string file_name); +SimTime* InitSimulationTime(std::string file_name); /** *@fn InitHipCatalogue *@brief Initialize function for HipparcosCatalogue class *@param [in] file_name: Path to the initialize function */ -HipparcosCatalogue* InitHipCatalogue(std::string file_name); +HipparcosCatalogue* InitHipparcosCatalogue(std::string file_name); /** *@fn InitCelesInfo *@brief Initialize function for CelestialInformation class *@param [in] file_name: Path to the initialize function */ -CelestialInformation* InitCelesInfo(std::string file_name); +CelestialInformation* InitCelestialInformation(std::string file_name); #endif // S2E_ENVIRONMENT_GLOBAL_INITIALIZE_GLOBAL_ENVIRONMENT_HPP_ From a0b8feb8ab71f0a0b36ef2c448845c1bebe01ddd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:09:01 +0100 Subject: [PATCH 0513/1086] Fix include files --- src/environment/global/simulation_time.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 812ac78bb..6116cdf57 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -12,12 +12,12 @@ #include // #include -#include -#include -#include - #include -#include + +#include "library/external/sgp4/sgp4ext.h" +#include "library/external/sgp4/sgp4io.h" +#include "library/external/sgp4/sgp4unit.h" +#include "library/logger/loggable.hpp" /** *@struct TimeState From bf3bfdc7c3d2227fb88ebb53d1ea35663deba707 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:15:45 +0100 Subject: [PATCH 0514/1086] Fix private member name --- src/environment/global/simulation_time.cpp | 54 +++++++++---------- src/environment/global/simulation_time.hpp | 62 +++++++++++----------- 2 files changed, 58 insertions(+), 58 deletions(-) diff --git a/src/environment/global/simulation_time.cpp b/src/environment/global/simulation_time.cpp index e40c55662..d949eb80b 100644 --- a/src/environment/global/simulation_time.cpp +++ b/src/environment/global/simulation_time.cpp @@ -30,15 +30,15 @@ SimTime::SimTime(const double end_sec, const double step_sec, const double attit thermal_update_interval_sec_ = thermal_update_interval_sec; thermal_rk_step_sec_ = thermal_rk_step_sec; log_output_interval_sec_ = log_output_interval_sec; - compo_update_interval_sec_ = compo_propagate_step_sec; - compo_propagate_frequency_ = int(1.0 / compo_update_interval_sec_); - sim_speed_ = sim_speed; - disp_period_ = (1.0 * end_sec / step_sec / 100); // Update every 1% + component_update_interval_sec_ = compo_propagate_step_sec; + component_propagate_frequency_Hz_ = int(1.0 / component_update_interval_sec_); + simulation_speed_ = sim_speed; + display_period_ = (1.0 * end_sec / step_sec / 100); // Update every 1% time_exceeds_continuously_limit_sec_ = 1.0; - // sscanf_s(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_mon_, &start_day_, &start_hr_, &start_min_, &start_sec_); - sscanf(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_mon_, &start_day_, &start_hr_, &start_min_, &start_sec_); - jday(start_year_, start_mon_, start_day_, start_hr_, start_min_, start_sec_, start_jd_); + // sscanf_s(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_min_, &start_sec_); + sscanf(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_min_, &start_sec_); + jday(start_year_, start_month_, start_day_, start_hour_, start_min_, start_sec_, start_jd_); current_jd_ = start_jd_; current_sidereal_ = gstime(current_jd_); JdToDecyear(current_jd_, ¤t_decyear_); @@ -60,7 +60,7 @@ void SimTime::AssertTimeStepParams() { assert(step_sec_ <= attitude_update_interval_sec_); assert(step_sec_ <= orbit_update_interval_sec_); assert(step_sec_ <= thermal_update_interval_sec_); - assert(step_sec_ <= compo_update_interval_sec_); + assert(step_sec_ <= component_update_interval_sec_); assert(step_sec_ <= log_output_interval_sec_); } @@ -72,20 +72,20 @@ void SimTime::SetParameters(void) { orbit_update_flag_ = false; thermal_update_counter_ = 1; thermal_update_flag_ = false; - compo_update_counter_ = 1; - compo_update_flag_ = false; + component_update_counter_ = 1; + component_update_flag_ = false; log_counter_ = 0; - disp_counter_ = 0; + display_counter_ = 0; state_.log_output = true; } void SimTime::UpdateTime(void) { InitializeState(); elapsed_time_sec_ += step_sec_; - if (sim_speed_ > 0) { + if (simulation_speed_ > 0) { chrono::system_clock clk; - int toWaitTime = - (int)(elapsed_time_sec_ * 1000 - chrono::duration_cast(clk.now() - clock_start_time_millisec_).count() * sim_speed_); + int toWaitTime = (int)(elapsed_time_sec_ * 1000 - + chrono::duration_cast(clk.now() - clock_start_time_millisec_).count() * simulation_speed_); if (toWaitTime <= 0) { // When the execution time is larger than specified step_sec @@ -97,7 +97,7 @@ void SimTime::UpdateTime(void) { // Forcibly set elapsed_tim_sec_ as actual elapsed time Reason: to catch up with real time when resume from a breakpoint elapsed_time_sec_ = - (chrono::duration_cast>>(clk.now() - clock_start_time_millisec_).count() * sim_speed_); + (chrono::duration_cast>>(clk.now() - clock_start_time_millisec_).count() * simulation_speed_); clock_last_time_completed_step_in_time_ = clk.now(); } @@ -116,9 +116,9 @@ void SimTime::UpdateTime(void) { attitude_update_counter_++; orbit_update_counter_++; thermal_update_counter_++; - compo_update_counter_++; + component_update_counter_++; log_counter_++; - disp_counter_++; + display_counter_++; if (elapsed_time_sec_ > end_sec_) { state_.finish = true; @@ -147,10 +147,10 @@ void SimTime::UpdateTime(void) { thermal_update_flag_ = true; } - compo_update_flag_ = false; - if (double(compo_update_counter_) * step_sec_ >= compo_update_interval_sec_) { - compo_update_counter_ = 0; - compo_update_flag_ = true; + component_update_flag_ = false; + if (double(component_update_counter_) * step_sec_ >= component_update_interval_sec_) { + component_update_counter_ = 0; + component_update_flag_ = true; } if (double(log_counter_) * step_sec_ >= log_output_interval_sec_) { @@ -158,8 +158,8 @@ void SimTime::UpdateTime(void) { state_.log_output = true; } - if (disp_counter_ >= disp_period_) { - disp_counter_ -= (int)disp_period_; + if (display_counter_ >= display_period_) { + display_counter_ -= (int)display_period_; state_.disp_output = true; } @@ -181,13 +181,13 @@ void SimTime::PrintStartDateTime(void) const { } else { m << start_min_; } - if (start_hr_ < 10) { - h << 0 << start_hr_; + if (start_hour_ < 10) { + h << 0 << start_hour_; } else { - h << start_hr_; + h << start_hour_; } - cout << " " << start_year_ << "/" << start_mon_ << "/" << start_day_ << " " << h.str() << ":" << m.str() << ":" << s.str() << "\n"; + cout << " " << start_year_ << "/" << start_month_ << "/" << start_day_ << " " << h.str() << ":" << m.str() << ":" << s.str() << "\n"; } string SimTime::GetLogHeader() const { diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 6116cdf57..e90989f94 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -159,17 +159,17 @@ class SimTime : public ILoggable { *@fn GetCompoStepSec *@brief Return component update step time [sec] */ - inline double GetCompoStepSec(void) const { return compo_update_interval_sec_; }; + inline double GetCompoStepSec(void) const { return component_update_interval_sec_; }; /** *@fn GetCompoUpdateFlag *@brief Return component update flag */ - inline bool GetCompoUpdateFlag() const { return compo_update_flag_; } + inline bool GetCompoUpdateFlag() const { return component_update_flag_; } /** *@fn GetCompoPropagateFrequency *@brief Return component propagate frequency [Hz] */ - inline int GetCompoPropagateFrequency(void) const { return compo_propagate_frequency_; }; + inline int GetCompoPropagateFrequency(void) const { return component_propagate_frequency_Hz_; }; /** *@fn GetEndSec @@ -212,7 +212,7 @@ class SimTime : public ILoggable { *@fn GetStartMon *@brief Return start time month [month] */ - inline int GetStartMon(void) const { return start_mon_; }; + inline int GetStartMon(void) const { return start_month_; }; /** *@fn GetStartDay *@brief Return start time day [day] @@ -222,7 +222,7 @@ class SimTime : public ILoggable { *@fn GetStartHr *@brief Return start time hour [hour] */ - inline int GetStartHr(void) const { return start_hr_; }; + inline int GetStartHr(void) const { return start_hour_; }; /** *@fn GetStartMin *@brief Return start time minute [minute] @@ -261,17 +261,17 @@ class SimTime : public ILoggable { UTC current_utc_; //!< UTC calendar day // Timing controller - int attitude_update_counter_; //!< Update counter for attitude calculation - bool attitude_update_flag_; //!< Update flag for attitude calculation - int orbit_update_counter_; //!< Update counter for orbit calculation - bool orbit_update_flag_; //!< Update flag for orbit calculation - int thermal_update_counter_; //!< Update counter for thermal calculation - bool thermal_update_flag_; //!< Update flag for thermal calculation - int compo_update_counter_; //!< Update counter for component calculation - bool compo_update_flag_; //!< Update flag for component calculation - int log_counter_; //!< Update counter for log output - int disp_counter_; //!< Update counter for display output - TimeState state_; //!< State of timing controller + int attitude_update_counter_; //!< Update counter for attitude calculation + bool attitude_update_flag_; //!< Update flag for attitude calculation + int orbit_update_counter_; //!< Update counter for orbit calculation + bool orbit_update_flag_; //!< Update flag for orbit calculation + int thermal_update_counter_; //!< Update counter for thermal calculation + bool thermal_update_flag_; //!< Update flag for thermal calculation + int component_update_counter_; //!< Update counter for component calculation + bool component_update_flag_; //!< Update flag for component calculation + int log_counter_; //!< Update counter for log output + int display_counter_; //!< Update counter for display output + TimeState state_; //!< State of timing controller // Calculation time measure std::chrono::system_clock::time_point clock_start_time_millisec_; //!< Simulation start time [ms] @@ -279,28 +279,28 @@ class SimTime : public ILoggable { std::chrono::system_clock::time_point clock_last_time_completed_step_in_time_; //!< Simulation finished time [ms] // Constants - double end_sec_; //!< Time from start of simulation to end [sec] - double step_sec_; //!< Simulation step width [sec] - double attitude_update_interval_sec_; //!< Update intercal for attitude calculation [sec] - double attitude_rk_step_sec_; //!< Runge-Kutta step width for attitude calculation [sec] - double orbit_update_interval_sec_; //!< Update intercal for orbit calculation [sec] - double orbit_rk_step_sec_; //!< Runge-Kutta step width for orbit calculation [sec] - double thermal_update_interval_sec_; //!< Update intercal for thermal calculation [sec] - double thermal_rk_step_sec_; //!< Runge-Kutta step width for thermal calculation [sec] - double compo_update_interval_sec_; //!< Update intercal for component calculation [sec] - int compo_propagate_frequency_; //!< Component propagation frequency [Hz] - double log_output_interval_sec_; //!< Log output interval [sec] - double disp_period_; //!< Display output period [sec] + double end_sec_; //!< Time from start of simulation to end [sec] + double step_sec_; //!< Simulation step width [sec] + double attitude_update_interval_sec_; //!< Update intercal for attitude calculation [sec] + double attitude_rk_step_sec_; //!< Runge-Kutta step width for attitude calculation [sec] + double orbit_update_interval_sec_; //!< Update intercal for orbit calculation [sec] + double orbit_rk_step_sec_; //!< Runge-Kutta step width for orbit calculation [sec] + double thermal_update_interval_sec_; //!< Update intercal for thermal calculation [sec] + double thermal_rk_step_sec_; //!< Runge-Kutta step width for thermal calculation [sec] + double component_update_interval_sec_; //!< Update intercal for component calculation [sec] + int component_propagate_frequency_Hz_; //!< Component propagation frequency [Hz] + double log_output_interval_sec_; //!< Log output interval [sec] + double display_period_; //!< Display output period [sec] double start_jd_; //!< Simulation start Julian date [day] int start_year_; //!< Simulation start year - int start_mon_; //!< Simulation start month + int start_month_; //!< Simulation start month int start_day_; //!< Simulation start day - int start_hr_; //!< Simulation start hour + int start_hour_; //!< Simulation start hour int start_min_; //!< Simulation start minute double start_sec_; //!< Simulation start seconds - double sim_speed_; //!< The speed of the simulation relative to real time (if negative, real time is not taken into account) + double simulation_speed_; //!< The speed of the simulation relative to real time (if negative, real time is not taken into account) double time_exceeds_continuously_limit_sec_; //!< Maximum duration to allow actual step_sec to be larger than specified continuously /** From bb9fd4889786f6b8c157b6b75c67320e161cd88d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:22:33 +0100 Subject: [PATCH 0515/1086] Fix min to minute --- src/components/real/aocs/gnss_receiver.cpp | 2 +- src/environment/global/simulation_time.cpp | 20 ++++++++++---------- src/environment/global/simulation_time.hpp | 6 +++--- 3 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 449f53ee1..bac8add7a 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -221,7 +221,7 @@ std::string GNSSReceiver::GetLogValue() const // For logs str_tmp += WriteScalar(utc_.month); str_tmp += WriteScalar(utc_.day); str_tmp += WriteScalar(utc_.hour); - str_tmp += WriteScalar(utc_.min); + str_tmp += WriteScalar(utc_.minute); str_tmp += WriteScalar(utc_.sec); str_tmp += WriteVector(position_eci_, 10); str_tmp += WriteVector(velocity_ecef_, 10); diff --git a/src/environment/global/simulation_time.cpp b/src/environment/global/simulation_time.cpp index d949eb80b..cb55542c9 100644 --- a/src/environment/global/simulation_time.cpp +++ b/src/environment/global/simulation_time.cpp @@ -36,9 +36,9 @@ SimTime::SimTime(const double end_sec, const double step_sec, const double attit display_period_ = (1.0 * end_sec / step_sec / 100); // Update every 1% time_exceeds_continuously_limit_sec_ = 1.0; - // sscanf_s(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_min_, &start_sec_); - sscanf(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_min_, &start_sec_); - jday(start_year_, start_month_, start_day_, start_hour_, start_min_, start_sec_, start_jd_); + // sscanf_s(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_minute_, &start_sec_); + sscanf(start_ymdhms, "%d/%d/%d %d:%d:%lf", &start_year_, &start_month_, &start_day_, &start_hour_, &start_minute_, &start_sec_); + jday(start_year_, start_month_, start_day_, start_hour_, start_minute_, start_sec_, start_jd_); current_jd_ = start_jd_; current_sidereal_ = gstime(current_jd_); JdToDecyear(current_jd_, ¤t_decyear_); @@ -176,10 +176,10 @@ void SimTime::PrintStartDateTime(void) const { } else { s << sec_int; } - if (start_min_ < 10) { - m << 0 << start_min_; + if (start_minute_ < 10) { + m << 0 << start_minute_; } else { - m << start_min_; + m << start_minute_; } if (start_hour_ < 10) { h << 0 << start_hour_; @@ -207,7 +207,7 @@ string SimTime::GetLogValue() const { const char kSize = 100; char ymdhms[kSize]; snprintf(ymdhms, kSize, "%4d/%02d/%02d %02d:%02d:%.3lf,", current_utc_.year, current_utc_.month, current_utc_.day, current_utc_.hour, - current_utc_.min, current_utc_.sec); + current_utc_.minute, current_utc_.sec); str_tmp += ymdhms; return str_tmp; @@ -222,13 +222,13 @@ void SimTime::InitializeState() { // wrapper function of invjday @ sgp4ext for interface adjustment void SimTime::ConvJDtoCalndarDay(const double JD) { - int year, mon, day, hr, min; + int year, mon, day, hr, minute; double sec; - invjday(JD, year, mon, day, hr, min, sec); + invjday(JD, year, mon, day, hr, minute, sec); current_utc_.year = (unsigned int)(year); current_utc_.month = (unsigned int)(mon); current_utc_.day = (unsigned int)(day); current_utc_.hour = (unsigned int)(hr); - current_utc_.min = (unsigned int)(min); + current_utc_.minute = (unsigned int)(minute); current_utc_.sec = sec; } diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index e90989f94..752dc97f2 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -39,7 +39,7 @@ struct UTC { unsigned int month = 1; unsigned int day = 1; unsigned int hour = 0; - unsigned int min = 0; + unsigned int minute = 0; double sec = 0.0; }; @@ -227,7 +227,7 @@ class SimTime : public ILoggable { *@fn GetStartMin *@brief Return start time minute [minute] */ - inline int GetStartMin(void) const { return start_min_; }; + inline int GetStartMin(void) const { return start_minute_; }; /** *@fn GetStartSec *@brief Return start time second [sec] @@ -297,7 +297,7 @@ class SimTime : public ILoggable { int start_month_; //!< Simulation start month int start_day_; //!< Simulation start day int start_hour_; //!< Simulation start hour - int start_min_; //!< Simulation start minute + int start_minute_; //!< Simulation start minute double start_sec_; //!< Simulation start seconds double simulation_speed_; //!< The speed of the simulation relative to real time (if negative, real time is not taken into account) From 63345ad635da2f1c38fa88c33fa35ef9ff9750f4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:23:45 +0100 Subject: [PATCH 0516/1086] Fix sec to second --- src/components/real/aocs/gnss_receiver.cpp | 2 +- src/environment/global/simulation_time.cpp | 4 ++-- src/environment/global/simulation_time.hpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index bac8add7a..7b35e2839 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -222,7 +222,7 @@ std::string GNSSReceiver::GetLogValue() const // For logs str_tmp += WriteScalar(utc_.day); str_tmp += WriteScalar(utc_.hour); str_tmp += WriteScalar(utc_.minute); - str_tmp += WriteScalar(utc_.sec); + str_tmp += WriteScalar(utc_.second); str_tmp += WriteVector(position_eci_, 10); str_tmp += WriteVector(velocity_ecef_, 10); str_tmp += WriteScalar(position_llh_[0], 10); diff --git a/src/environment/global/simulation_time.cpp b/src/environment/global/simulation_time.cpp index cb55542c9..75f224fed 100644 --- a/src/environment/global/simulation_time.cpp +++ b/src/environment/global/simulation_time.cpp @@ -207,7 +207,7 @@ string SimTime::GetLogValue() const { const char kSize = 100; char ymdhms[kSize]; snprintf(ymdhms, kSize, "%4d/%02d/%02d %02d:%02d:%.3lf,", current_utc_.year, current_utc_.month, current_utc_.day, current_utc_.hour, - current_utc_.minute, current_utc_.sec); + current_utc_.minute, current_utc_.second); str_tmp += ymdhms; return str_tmp; @@ -230,5 +230,5 @@ void SimTime::ConvJDtoCalndarDay(const double JD) { current_utc_.day = (unsigned int)(day); current_utc_.hour = (unsigned int)(hr); current_utc_.minute = (unsigned int)(minute); - current_utc_.sec = sec; + current_utc_.second = sec; } diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 752dc97f2..97d55baca 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -40,7 +40,7 @@ struct UTC { unsigned int day = 1; unsigned int hour = 0; unsigned int minute = 0; - double sec = 0.0; + double second = 0.0; }; /** From 335d87a58d36f0513eae8359410c428cbf376fd3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:34:08 +0100 Subject: [PATCH 0517/1086] Fix public function name --- src/components/real/aocs/gnss_receiver.cpp | 8 +- src/dynamics/dynamics.cpp | 14 ++-- src/environment/global/global_environment.cpp | 4 +- src/environment/global/gnss_satellites.cpp | 14 ++-- src/environment/global/simulation_time.hpp | 74 +++++++++---------- src/environment/local/local_environment.cpp | 4 +- src/simulation/case/sample_case.cpp | 2 +- .../sample_spacecraft/sample_components.cpp | 11 +-- 8 files changed, 66 insertions(+), 65 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 7b35e2839..c4535cb5d 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -59,13 +59,13 @@ void GNSSReceiver::MainRoutine(int count) { velocity_ecef_ = dynamics_->GetOrbit().GetSatVelocity_ecef(); AddNoise(pos_true_eci_, position_ecef_); - utc_ = simtime_->GetCurrentUTC(); - ConvertJulianDayToGPSTime(simtime_->GetCurrentJd()); + utc_ = simtime_->GetCurrentUtc(); + ConvertJulianDayToGPSTime(simtime_->GetCurrentTime_jd()); } else { // position information will not be updated in this case // only time information will be updated in this case (according to the receiver's internal clock) - utc_ = simtime_->GetCurrentUTC(); - ConvertJulianDayToGPSTime(simtime_->GetCurrentJd()); + utc_ = simtime_->GetCurrentUtc(); + ConvertJulianDayToGPSTime(simtime_->GetCurrentTime_jd()); } } diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 280a0c93e..f0df0b540 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -25,11 +25,11 @@ void Dynamics::Initialize(SimulationConfig* sim_config, const SimTime* sim_time, structure_ = structure; // Initialize - orbit_ = InitOrbit(&(local_celes_info->GetGlobalInfo()), sim_config->sat_file_[sat_id], sim_time->GetOrbitRKStepSec(), sim_time->GetCurrentJd(), - local_celes_info->GetGlobalInfo().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", rel_info); - attitude_ = InitAttitude(sim_config->sat_file_[sat_id], orbit_, local_celes_info, sim_time->GetAttitudeRKStepSec(), + orbit_ = InitOrbit(&(local_celes_info->GetGlobalInfo()), sim_config->sat_file_[sat_id], sim_time->GetOrbitRkStepTime_s(), + sim_time->GetCurrentTime_jd(), local_celes_info->GetGlobalInfo().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", rel_info); + attitude_ = InitAttitude(sim_config->sat_file_[sat_id], orbit_, local_celes_info, sim_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor(), sat_id); - temperature_ = InitTemperature(sim_config->sat_file_[sat_id], sim_time->GetThermalRKStepSec()); + temperature_ = InitTemperature(sim_config->sat_file_[sat_id], sim_time->GetThermalRkStepTime_s()); // To get initial value orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); @@ -38,11 +38,11 @@ void Dynamics::Initialize(SimulationConfig* sim_config, const SimTime* sim_time, void Dynamics::Update(const SimTime* sim_time, const LocalCelestialInformation* local_celes_info) { // Attitude propagation if (sim_time->GetAttitudePropagateFlag()) { - attitude_->Propagate(sim_time->GetElapsedSec()); + attitude_->Propagate(sim_time->GetElapsedTime_s()); } // Orbit Propagation if (sim_time->GetOrbitPropagateFlag()) { - orbit_->Propagate(sim_time->GetElapsedSec(), sim_time->GetCurrentJd()); + orbit_->Propagate(sim_time->GetElapsedTime_s(), sim_time->GetCurrentTime_jd()); } // Attitude dependent update orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); @@ -52,7 +52,7 @@ void Dynamics::Update(const SimTime* sim_time, const LocalCelestialInformation* std::string sun_str = "SUN"; char* c_sun = new char[sun_str.size() + 1]; std::char_traits::copy(c_sun, sun_str.c_str(), sun_str.size() + 1); // string -> char* - temperature_->Propagate(local_celes_info->GetPosFromSC_b(c_sun), sim_time->GetElapsedSec()); + temperature_->Propagate(local_celes_info->GetPosFromSC_b(c_sun), sim_time->GetElapsedTime_s()); delete[] c_sun; } } diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 715dc1f2c..c6ee8634b 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -30,13 +30,13 @@ void GlobalEnvironment::Initialize(SimulationConfig* simulation_configuration) { gnss_satellites_ = InitGnssSatellites(simulation_configuration->gnss_file_); // Calc initial value - celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentJd()); + celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentTime_jd()); gnss_satellites_->SetUp(simulation_time_); } void GlobalEnvironment::Update() { simulation_time_->UpdateTime(); - celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentJd()); + celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentTime_jd()); gnss_satellites_->Update(simulation_time_); } diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 5049b1120..f02d0ff3f 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -863,16 +863,16 @@ void GnssSatellites::SetUp(const SimTime* sim_time) { tm* start_tm = initilized_tm(); start_tm->tm_year = sim_time->GetStartYear() - 1900; - start_tm->tm_mon = sim_time->GetStartMon() - 1; + start_tm->tm_mon = sim_time->GetStartMonth() - 1; start_tm->tm_mday = sim_time->GetStartDay(); - start_tm->tm_hour = sim_time->GetStartHr(); - start_tm->tm_min = sim_time->GetStartMin(); - double start_sec = sim_time->GetStartSec(); + start_tm->tm_hour = sim_time->GetStartHour(); + start_tm->tm_min = sim_time->GetStartMinute(); + double start_sec = sim_time->GetStartSecond(); start_tm->tm_sec = (int)start_sec; double unix_time = (double)mktime(start_tm) + start_sec - floor(start_sec); std::free(start_tm); - true_info_.SetUp(unix_time, sim_time->GetStepSec()); - estimate_info_.SetUp(unix_time, sim_time->GetStepSec()); + true_info_.SetUp(unix_time, sim_time->GetSimulationStep_s()); + estimate_info_.SetUp(unix_time, sim_time->GetSimulationStep_s()); start_unix_time_ = unix_time; @@ -882,7 +882,7 @@ void GnssSatellites::SetUp(const SimTime* sim_time) { void GnssSatellites::Update(const SimTime* sim_time) { if (!IsCalcEnabled()) return; - double elapsed_sec = sim_time->GetElapsedSec(); + double elapsed_sec = sim_time->GetElapsedTime_s(); true_info_.Update(elapsed_sec + start_unix_time_); estimate_info_.Update(elapsed_sec + start_unix_time_); diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 97d55baca..bee1a1da5 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -98,84 +98,84 @@ class SimTime : public ILoggable { */ inline const TimeState GetState(void) const { return state_; }; /** - *@fn GetElapsedSec + *@fn GetElapsedTime_s *@brief Return simulation elapsed time [sec] */ - inline double GetElapsedSec(void) const { return elapsed_time_sec_; }; + inline double GetElapsedTime_s(void) const { return elapsed_time_sec_; }; /** - *@fn GetStepSec + *@fn GetSimulationStep_s *@brief Return simulation step [sec] */ - inline double GetStepSec(void) const { return step_sec_; }; + inline double GetSimulationStep_s(void) const { return step_sec_; }; /** - *@fn GetAttitudeUpdateIntervalSec + *@fn GetAttitudeUpdateInterval_s *@brief Return attitude update interval [sec] */ - inline double GetAttitudeUpdateIntervalSec(void) const { return attitude_update_interval_sec_; }; + inline double GetAttitudeUpdateInterval_s(void) const { return attitude_update_interval_sec_; }; /** *@fn GetAttitudePropagateFlag *@brief Return attitude propagate flag */ inline bool GetAttitudePropagateFlag(void) const { return attitude_update_flag_; }; /** - *@fn GetAttitudeRKStepSec + *@fn GetAttitudeRkStepTime_s *@brief Return attitude Runge-Kutta step time [sec] */ - inline double GetAttitudeRKStepSec() const { return attitude_rk_step_sec_; } + inline double GetAttitudeRkStepTime_s() const { return attitude_rk_step_sec_; } /** - *@fn GetOrbitUpdateIntervalSec + *@fn GetOrbitUpdateInterval_s *@brief Return orbit update interval [sec] */ - inline double GetOrbitUpdateIntervalSec(void) const { return orbit_update_interval_sec_; }; + inline double GetOrbitUpdateInterval_s(void) const { return orbit_update_interval_sec_; }; /** *@fn GetOrbitPropagateFlag *@brief Return orbit propagate flag */ inline bool GetOrbitPropagateFlag(void) const { return orbit_update_flag_; }; /** - *@fn GetOrbitRKStepSec + *@fn GetOrbitRkStepTime_s *@brief Return orbit Runge-Kutta step time [sec] */ - inline double GetOrbitRKStepSec() const { return orbit_rk_step_sec_; } + inline double GetOrbitRkStepTime_s() const { return orbit_rk_step_sec_; } /** *@fn GetThermalUpdateIntervalSec *@brief Return thermal update interval [sec] */ - inline double GetThermalUpdateIntervalSec(void) const { return thermal_update_interval_sec_; }; + inline double GetThermalUpdateInterval_s(void) const { return thermal_update_interval_sec_; }; /** *@fn GetThermalPropagateFlag *@brief Return thermal propagate flag */ inline bool GetThermalPropagateFlag(void) const { return thermal_update_flag_; }; /** - *@fn GetThermalRKStepSec + *@fn GetThermalRkStepTime_s *@brief Return thermal Runge-Kutta step time [sec] */ - inline double GetThermalRKStepSec() const { return thermal_rk_step_sec_; } + inline double GetThermalRkStepTime_s() const { return thermal_rk_step_sec_; } /** - *@fn GetCompoStepSec + *@fn GetComponentStepTime_s *@brief Return component update step time [sec] */ - inline double GetCompoStepSec(void) const { return component_update_interval_sec_; }; + inline double GetComponentStepTime_s(void) const { return component_update_interval_sec_; }; /** *@fn GetCompoUpdateFlag *@brief Return component update flag */ inline bool GetCompoUpdateFlag() const { return component_update_flag_; } /** - *@fn GetCompoPropagateFrequency + *@fn GetComponentPropagateFrequency_Hz *@brief Return component propagate frequency [Hz] */ - inline int GetCompoPropagateFrequency(void) const { return component_propagate_frequency_Hz_; }; + inline int GetComponentPropagateFrequency_Hz(void) const { return component_propagate_frequency_Hz_; }; /** - *@fn GetEndSec + *@fn GetEndTime_s *@brief Return simulation end elapsed time [sec] */ - inline double GetEndSec(void) const { return end_sec_; }; + inline double GetEndTime_s(void) const { return end_sec_; }; /** *@fn GetProgressionRate *@brief Return progression rate of the simulation [%] @@ -183,25 +183,25 @@ class SimTime : public ILoggable { inline int GetProgressionRate(void) const { return (int)floor((elapsed_time_sec_ / end_sec_ * 100)); }; /** - *@fn GetCurrentJd + *@fn GetCurrentTime_jd *@brief Return current Julian day [day] */ - inline double GetCurrentJd(void) const { return current_jd_; }; + inline double GetCurrentTime_jd(void) const { return current_jd_; }; /** - *@fn GetCurrentSidereal + *@fn GetCurrentSiderealTime *@brief Return current sidereal day [day] */ - inline double GetCurrentSidereal(void) const { return current_sidereal_; }; + inline double GetCurrentSiderealTime(void) const { return current_sidereal_; }; /** - *@fn GetCurrentDecyear + *@fn GetCurrentDecimalYear *@brief Return current decimal year [year] */ - inline double GetCurrentDecyear(void) const { return current_decyear_; }; + inline double GetCurrentDecimalYear(void) const { return current_decyear_; }; /** - *@fn GetCurrentUTC + *@fn GetCurrentUtc *@brief Return current UTC calendar expression */ - inline const UTC GetCurrentUTC(void) const { return current_utc_; }; + inline const UTC GetCurrentUtc(void) const { return current_utc_; }; /** *@fn GetStartYear @@ -209,30 +209,30 @@ class SimTime : public ILoggable { */ inline int GetStartYear(void) const { return start_year_; }; /** - *@fn GetStartMon + *@fn GetStartMonth *@brief Return start time month [month] */ - inline int GetStartMon(void) const { return start_month_; }; + inline int GetStartMonth(void) const { return start_month_; }; /** *@fn GetStartDay *@brief Return start time day [day] */ inline int GetStartDay(void) const { return start_day_; }; /** - *@fn GetStartHr + *@fn GetStartHour *@brief Return start time hour [hour] */ - inline int GetStartHr(void) const { return start_hour_; }; + inline int GetStartHour(void) const { return start_hour_; }; /** - *@fn GetStartMin + *@fn GetStartMinute *@brief Return start time minute [minute] */ - inline int GetStartMin(void) const { return start_minute_; }; + inline int GetStartMinute(void) const { return start_minute_; }; /** - *@fn GetStartSec + *@fn GetStartSecond *@brief Return start time second [sec] */ - inline double GetStartSec(void) const { return start_sec_; }; + inline double GetStartSecond(void) const { return start_sec_; }; // Override ILoggable /** diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 0ea0ee464..78b1eb4c1 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -50,13 +50,13 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { celes_info_->UpdateAllObjectsInfo(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); - mag_->CalcMag(sim_time->GetCurrentDecyear(), sim_time->GetCurrentSidereal(), orbit.GetLatLonAlt(), attitude.GetQuaternion_i2b()); + mag_->CalcMag(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetLatLonAlt(), attitude.GetQuaternion_i2b()); } // Update local environments that depend only on the position if (sim_time->GetOrbitPropagateFlag()) { srp_->UpdateAllStates(); - atmosphere_->CalcAirDensity(sim_time->GetCurrentDecyear(), sim_time->GetEndSec(), orbit.GetLatLonAlt()); + atmosphere_->CalcAirDensity(sim_time->GetCurrentDecimalYear(), sim_time->GetEndTime_s(), orbit.GetLatLonAlt()); } } diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index cdf879941..df3b3b44f 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -78,7 +78,7 @@ string SampleCase::GetLogValue() const { // auto omega_b = sample_sat->dynamics_->GetAttitude().GetOmega_b(); // Need to match the contents of log with header setting above - str_tmp += WriteScalar(glo_env_->GetSimulationTime().GetElapsedSec()); + str_tmp += WriteScalar(glo_env_->GetSimulationTime().GetElapsedTime_s()); // str_tmp += WriteVector(pos_i, 16); // str_tmp += WriteVector(vel_i, 10); // str_tmp += WriteQuaternion(quat_i2b); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 571844570..a93be745d 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -27,18 +27,19 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Gyro std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), dynamics_)); + gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // MagSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_sensor_ = new MagSensor( - InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), &(local_env_->GetMag()))); + InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetMag()))); // STT ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - stt_ = new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), dynamics_, local_env_)); + stt_ = + new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); @@ -55,13 +56,13 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); mag_torquer_ = new MagTorquer( - InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetCompoStepSec(), &(local_env_->GetMag()))); + InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetMag()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); config_->main_logger_->CopyFileToLogDir(ini_path); rw_ = new RWModel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), - glo_env_->GetSimulationTime().GetCompoStepSec())); + glo_env_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); From 52537c78ab677a59933920c61fe3d650b13e65c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:42:13 +0100 Subject: [PATCH 0518/1086] Remove using and unused include files --- src/environment/local/atmosphere.cpp | 32 +++++++++++----------------- src/environment/local/atmosphere.hpp | 11 ++++------ 2 files changed, 16 insertions(+), 27 deletions(-) diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index fe522227e..225ddc3a6 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -5,21 +5,13 @@ #include "atmosphere.hpp" -#include -#include -#include -#include -#include +#include "library/logger/log_utility.hpp" +#include "library/math/vector.hpp" +#include "library/randomization/global_randomization.hpp" +#include "library/randomization/normal_randomization.hpp" +#include "library/randomization/random_walk.hpp" -using libra::NormalRand; -using libra::Vector; - -using std::cerr; -using std::endl; -using std::string; -using namespace libra; - -Atmosphere::Atmosphere(string model, string fname, double gauss_stddev, bool is_manual_param_used, double manual_daily_f107, +Atmosphere::Atmosphere(std::string model, std::string fname, double gauss_stddev, bool is_manual_param_used, double manual_daily_f107, double manual_average_f107, double manual_ap) : model_(model), fname_(fname), @@ -47,7 +39,7 @@ int Atmosphere::GetSpaceWeatherTable(double decyear, double endsec) { double Atmosphere::GetAirDensity() const { return air_density_; } -double Atmosphere::CalcAirDensity(double decyear, double endsec, Vector<3> lat_lon_alt) { +double Atmosphere::CalcAirDensity(double decyear, double endsec, libra::Vector<3> lat_lon_alt) { if (!IsCalcEnabled) return 0; if (model_ == "STANDARD") { @@ -211,21 +203,21 @@ double Atmosphere::CalcStandard(double altitude_m) { double Atmosphere::AddNoise(double rho) { // RandomWalk rw(rho*rw_stepwidth_,rho*rw_stddev_,rho*rw_limit_); - NormalRand nr(0.0, rho * gauss_stddev_, g_rand.MakeSeed()); + libra::NormalRand nr(0.0, rho * gauss_stddev_, g_rand.MakeSeed()); double nrd = nr; return rho + nrd; } -string Atmosphere::GetLogValue() const { - string str_tmp = ""; +std::string Atmosphere::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteScalar(air_density_); return str_tmp; } -string Atmosphere::GetLogHeader() const { - string str_tmp = ""; +std::string Atmosphere::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteScalar("air_density_at_spacecraft_position", "kg/m3"); diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 180591eac..5713b7897 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -7,15 +7,12 @@ #ifndef S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ #define S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ -#include -#include -#include -#include #include #include -using libra::Quaternion; -using libra::Vector; +#include "library/external/nrlmsise00/wrapper_nrlmsise00.hpp" +#include "library/logger/loggable.hpp" +#include "library/math/vector.hpp" /** * @class Atmosphere @@ -51,7 +48,7 @@ class Atmosphere : public ILoggable { * @param [in] lat_lon_alt: Latitude[rad], longitude[rad], and altitude[m] * @return Atmospheric density [kg/m^3] */ - double CalcAirDensity(double decyear, double endsec, Vector<3> lat_lon_alt); + double CalcAirDensity(double decyear, double endsec, libra::Vector<3> lat_lon_alt); /** * @fn GetAirDensity * @brief Return Atmospheric density [kg/m^3] From 271b4b09c1c3e10a81d0f769b46c0c1921f2ff12 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 11:55:32 +0100 Subject: [PATCH 0519/1086] Fix private member names --- src/environment/local/atmosphere.cpp | 51 ++++++++++++++-------------- src/environment/local/atmosphere.hpp | 41 +++++++++++----------- 2 files changed, 47 insertions(+), 45 deletions(-) diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 225ddc3a6..165656219 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -11,13 +11,13 @@ #include "library/randomization/normal_randomization.hpp" #include "library/randomization/random_walk.hpp" -Atmosphere::Atmosphere(std::string model, std::string fname, double gauss_stddev, bool is_manual_param_used, double manual_daily_f107, - double manual_average_f107, double manual_ap) +Atmosphere::Atmosphere(std::string model, std::string initialize_file_name, double gauss_standard_deviation_rate, bool is_manual_param_used, + double manual_daily_f107, double manual_average_f107, double manual_ap) : model_(model), - fname_(fname), - air_density_(0.0), - gauss_stddev_(gauss_stddev), - is_table_imported_(false), + initialize_file_name_(initialize_file_name), + air_density_kg_m3_(0.0), + gauss_standard_deviation_rate_(gauss_standard_deviation_rate), + is_space_weather_table_imported_(false), is_manual_param_used_(is_manual_param_used), manual_daily_f107_(manual_daily_f107), manual_average_f107_(manual_average_f107), @@ -32,25 +32,25 @@ Atmosphere::Atmosphere(std::string model, std::string fname, double gauss_stddev } } -int Atmosphere::GetSpaceWeatherTable(double decyear, double endsec) { +int Atmosphere::GetSpaceWeatherTable(double decimal_year, double end_time_s) { // Get table of simulation duration only to decrease memory - return GetSpaceWeatherTable_(decyear, endsec, fname_, table_); + return GetSpaceWeatherTable_(decimal_year, end_time_s, initialize_file_name_, space_weather_table_); } -double Atmosphere::GetAirDensity() const { return air_density_; } +double Atmosphere::GetAirDensity() const { return air_density_kg_m3_; } -double Atmosphere::CalcAirDensity(double decyear, double endsec, libra::Vector<3> lat_lon_alt) { +double Atmosphere::CalcAirDensity(double decimal_year, double end_time_s, libra::Vector<3> lat_lon_alt) { if (!IsCalcEnabled) return 0; if (model_ == "STANDARD") { double altitude_m = lat_lon_alt(2); - air_density_ = CalcStandard(altitude_m); + air_density_kg_m3_ = CalcStandard(altitude_m); } else if (model_ == "NRLMSISE00") // NRLMSISE00 model { if (!is_manual_param_used_) { - if (!is_table_imported_) { - if (GetSpaceWeatherTable(decyear, endsec)) { - is_table_imported_ = true; + if (!is_space_weather_table_imported_) { + if (GetSpaceWeatherTable(decimal_year, end_time_s)) { + is_space_weather_table_imported_ = true; } else { std::cerr << "Air density is switched to STANDARD model" << std::endl; model_ = "STANDARD"; @@ -61,13 +61,14 @@ double Atmosphere::CalcAirDensity(double decyear, double endsec, libra::Vector<3 double latrad = lat_lon_alt(0); double lonrad = lat_lon_alt(1); double alt = lat_lon_alt(2); - air_density_ = CalcNRLMSISE00(decyear, latrad, lonrad, alt, table_, is_manual_param_used_, manual_daily_f107_, manual_average_f107_, manual_ap_); + air_density_kg_m3_ = CalcNRLMSISE00(decimal_year, latrad, lonrad, alt, space_weather_table_, is_manual_param_used_, manual_daily_f107_, + manual_average_f107_, manual_ap_); } else { // No suitable model - return air_density_ = 0.0; + return air_density_kg_m3_ = 0.0; } - return AddNoise(air_density_); + return AddNoise(air_density_kg_m3_); } double Atmosphere::CalcStandard(double altitude_m) { @@ -197,21 +198,21 @@ double Atmosphere::CalcStandard(double altitude_m) { return 0.0; } - double rho = baseRho * exp(-(altitude - baseHeight) / scaleHeight); - return rho; + double rho_kg_m3 = baseRho * exp(-(altitude - baseHeight) / scaleHeight); + return rho_kg_m3; } -double Atmosphere::AddNoise(double rho) { - // RandomWalk rw(rho*rw_stepwidth_,rho*rw_stddev_,rho*rw_limit_); - libra::NormalRand nr(0.0, rho * gauss_stddev_, g_rand.MakeSeed()); +double Atmosphere::AddNoise(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_, g_rand.MakeSeed()); double nrd = nr; - return rho + nrd; + return rho_kg_m3 + nrd; } std::string Atmosphere::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(air_density_); + str_tmp += WriteScalar(air_density_kg_m3_); return str_tmp; } @@ -219,7 +220,7 @@ std::string Atmosphere::GetLogValue() const { std::string Atmosphere::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("air_density_at_spacecraft_position", "kg/m3"); + str_tmp += WriteScalar("air_density_kg_m3_at_spacecraft_position", "kg/m3"); return str_tmp; } diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 5713b7897..12c6c20e2 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -26,15 +26,15 @@ class Atmosphere : public ILoggable { * @fn Atmosphere * @brief Constructor * @param [in] model: Atmospheric density model name - * @param [in] fname: Path and name of initialize file - * @param [in] gauss_stddev: Standard deviation of density noise (defined as percentage) + * @param [in] initialize_file_name: Path and name of initialize file + * @param [in] gauss_standard_deviation_rate: Standard deviation of density noise (defined as percentage) * @param [in] is_manual_param: Flag to use manual parameters * @param [in] manual_f107: Manual value of daily F10.7 * @param [in] manual_f107a: Manual value of averaged F10.7 (3-month averaged value) * @param [in] manual_ap: Manual value of ap value */ - Atmosphere(std::string model, std::string fname, double gauss_stddev, bool is_manual_param, double manual_f107, double manual_f107a, - double manual_ap); + Atmosphere(std::string model, std::string initialize_file_name, double gauss_standard_deviation_rate, bool is_manual_param, double manual_f107, + double manual_f107a, double manual_ap); /** * @fn ~Atmosphere * @brief Destructor @@ -43,12 +43,12 @@ class Atmosphere : public ILoggable { /** * @fn CalcAirDensity * @brief Calculate atmospheric density - * @param [in] decyear: Decimal year of simulation start [year] - * @param [in] endsec: End time of simulation [sec] - * @param [in] lat_lon_alt: Latitude[rad], longitude[rad], and altitude[m] + * @param [in] decimal_year: Decimal year of simulation start [year] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] lat_lon_alt: Latitude[rad], longitude[rad], and altitude[m] TODO: change to use geodetic position * @return Atmospheric density [kg/m^3] */ - double CalcAirDensity(double decyear, double endsec, libra::Vector<3> lat_lon_alt); + double CalcAirDensity(double decimal_year, double end_time_s, libra::Vector<3> lat_lon_alt); /** * @fn GetAirDensity * @brief Return Atmospheric density [kg/m^3] @@ -68,19 +68,20 @@ class Atmosphere : public ILoggable { virtual std::string GetLogValue() const; private: - std::string model_; //!< Atmospheric density model name - std::string fname_; //!< Path and name of initialize file - double air_density_; //!< Atmospheric density [kg/m^3] - double gauss_stddev_; //!< Standard deviation of density noise (defined as percentage) - std::vector table_; //!< Space weather table - bool is_table_imported_; //!< Flag of the space weather table is imported or not - bool is_manual_param_used_; //!< Flag to use manual parameters + std::string model_; //!< Atmospheric density model name + std::string initialize_file_name_; //!< Path and name of initialize file + double air_density_kg_m3_; //!< Atmospheric density [kg/m^3] + double gauss_standard_deviation_rate_; //!< Standard deviation of density noise (defined as percentage) + std::vector space_weather_table_; //!< Space weather table + bool is_space_weather_table_imported_; //!< Flag of the space weather table is imported or not + bool is_manual_param_used_; //!< Flag to use manual parameters // Reference of the following setting parameters https://www.swpc.noaa.gov/phenomena/f107-cm-radio-emissions double manual_daily_f107_; //!< Manual daily f10.7 value double manual_average_f107_; //!< Manual 3-month averaged f10.7 value double manual_ap_; //!< Manual ap value Ref: http://wdc.kugi.kyoto-u.ac.jp/kp/kpexp-j.html + // TODO: Add random walk noise // double rw_stepwidth_; // double rw_stddev_; // double rw_limit_; @@ -94,19 +95,19 @@ class Atmosphere : public ILoggable { double CalcStandard(double altitude_m); /** * @fn GetSpaceWeatherTable - * @param [in] decyear: Decimal year of simulation start [year] - * @param [in] endsec: End time of simulation [sec] + * @param [in] decimal_year: Decimal year of simulation start [year] + * @param [in] end_time_s: End time of simulation [sec] * @return Size of table */ - int GetSpaceWeatherTable(double decyear, double endsec); + int GetSpaceWeatherTable(double decimal_year, double end_time_s); /** * @fn AddNoise * @brief Add atmospheric density noise - * @param [in] rho: True atmospheric density [kg/m^3] + * @param [in] rho_kg_m3: True atmospheric density [kg/m^3] * @return Atmospheric density with noise [kg/m^3] */ - double AddNoise(double rho); + double AddNoise(double rho_kg_m3); }; #endif // S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ From 967214e5d81728fd946c62e5da9c72dc4ebd8b6f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 12:00:41 +0100 Subject: [PATCH 0520/1086] Fix local variables and Public function name --- src/disturbances/air_drag.cpp | 2 +- src/environment/local/atmosphere.cpp | 249 +++++++++++++-------------- src/environment/local/atmosphere.hpp | 2 +- 3 files changed, 125 insertions(+), 128 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index bb968c73d..2612d1522 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -23,7 +23,7 @@ AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center } void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - double air_density_kg_m3 = local_environment.GetAtmosphere().GetAirDensity(); + double air_density_kg_m3 = local_environment.GetAtmosphere().GetAirDensity_kg_m3(); Vector<3> velocity_b_m_s = dynamics.GetOrbit().GetSatVelocity_b(); CalcTorqueForce(velocity_b_m_s, air_density_kg_m3); } diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 165656219..4a5239f24 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -37,8 +37,6 @@ int Atmosphere::GetSpaceWeatherTable(double decimal_year, double end_time_s) { return GetSpaceWeatherTable_(decimal_year, end_time_s, initialize_file_name_, space_weather_table_); } -double Atmosphere::GetAirDensity() const { return air_density_kg_m3_; } - double Atmosphere::CalcAirDensity(double decimal_year, double end_time_s, libra::Vector<3> lat_lon_alt) { if (!IsCalcEnabled) return 0; @@ -72,133 +70,132 @@ double Atmosphere::CalcAirDensity(double decimal_year, double end_time_s, libra: } double Atmosphere::CalcStandard(double altitude_m) { - // altitude_mの単位は[m] - double altitude = altitude_m / 1000.0; // Convert to km - double scaleHeight; // [km] - double baseHeight; // [km] - double baseRho; // [kg/m^3] - - // scaleHeight values: Ref "ミッション解析と軌道設計の基礎" (in Japanese) - if (altitude > 1000.0) { - scaleHeight = 268.0; - baseHeight = 1000.0; - baseRho = 3.019E-15; - } else if (altitude >= 900.0 && altitude < 1000.0) { - scaleHeight = 181.05; - baseHeight = 900.0; - baseRho = 5.245E-15; - } else if (altitude >= 800.0 && altitude < 900.0) { - scaleHeight = 124.64; - baseHeight = 800.0; - baseRho = 1.170E-14; - } else if (altitude >= 700.0 && altitude < 800.0) { - scaleHeight = 88.667; - baseHeight = 700.0; - baseRho = 3.614E-14; - } else if (altitude >= 600.0 && altitude < 700.0) { - scaleHeight = 71.835; - baseHeight = 600.0; - baseRho = 1.454E-13; - } else if (altitude >= 500.0 && altitude < 600.0) { - scaleHeight = 63.822; - baseHeight = 500.0; - baseRho = 6.967E-13; - } else if (altitude >= 450.0 && altitude < 500.0) { - scaleHeight = 60.828; - baseHeight = 450.0; - baseRho = 1.585E-12; - } else if (altitude >= 400.0 && altitude < 450.0) { - scaleHeight = 58.515; - baseHeight = 400.0; - baseRho = 3.725E-12; - } else if (altitude >= 350.0 && altitude < 400.0) { - scaleHeight = 53.298; - baseHeight = 350.0; - baseRho = 9.158E-12; - } else if (altitude >= 300.0 && altitude < 350.0) { - scaleHeight = 53.628; - baseHeight = 300.0; - baseRho = 2.418E-11; - } else if (altitude >= 250.0 && altitude < 300.0) { - scaleHeight = 45.546; - baseHeight = 250.0; - baseRho = 7.248E-11; - } else if (altitude >= 200.0 && altitude < 250.0) { - scaleHeight = 37.105; - baseHeight = 200.0; - baseRho = 2.789E-10; - } else if (altitude >= 180.0 && altitude < 200.0) { - scaleHeight = 29.740; - baseHeight = 180.0; - baseRho = 5.464E-10; - } else if (altitude >= 150.0 && altitude < 180.0) { - scaleHeight = 22.523; - baseHeight = 150.0; - baseRho = 2.070E-9; - } else if (altitude >= 140.0 && altitude < 150.0) { - scaleHeight = 16.149; - baseHeight = 140.0; - baseRho = 3.845E-9; - } else if (altitude >= 130.0 && altitude < 140.0) { - scaleHeight = 12.636; - baseHeight = 130.0; - baseRho = 8.484E-9; - } else if (altitude >= 120.0 && altitude < 130.0) { - scaleHeight = 9.473; - baseHeight = 120.0; - baseRho = 2.438E-8; - } else if (altitude >= 110.0 && altitude < 120.0) { - scaleHeight = 7.263; - baseHeight = 110.0; - baseRho = 9.661E-8; - } else if (altitude >= 100.0 && altitude < 110.0) { - scaleHeight = 5.877; - baseHeight = 100.0; - baseRho = 5.297E-7; - } else if (altitude >= 90.0 && altitude < 100.0) { - scaleHeight = 5.382; - baseHeight = 90.0; - baseRho = 3.396E-6; - } else if (altitude >= 80.0 && altitude < 90.0) { - scaleHeight = 5.799; - baseHeight = 80.0; - baseRho = 1.905E-5; - } else if (altitude >= 70.0 && altitude < 80.0) { - scaleHeight = 6.549; - baseHeight = 70.0; - baseRho = 8.770E-5; - } else if (altitude >= 60.0 && altitude < 70.0) { - scaleHeight = 7.714; - baseHeight = 60.0; - baseRho = 3.206E-4; - } else if (altitude >= 50.0 && altitude < 60.0) { - scaleHeight = 8.382; - baseHeight = 50.0; - baseRho = 1.057E-3; - } else if (altitude >= 40.0 && altitude < 50.0) { - scaleHeight = 7.554; - baseHeight = 40.0; - baseRho = 3.972E-3; - } else if (altitude >= 30.0 && altitude < 40.0) { - scaleHeight = 6.682; - baseHeight = 30.0; - baseRho = 1.774E-2; - } else if (altitude >= 25.0 && altitude < 30.0) { - scaleHeight = 6.349; - baseHeight = 25.0; - baseRho = 3.899E-2; - } else if (altitude >= 0.0 && altitude < 25.0) { - scaleHeight = 7.249; - baseHeight = 0.0; - baseRho = 1.225; - } else { // In case of altitude is minus value - scaleHeight = 7.249; - baseHeight = 0.0; - baseRho = 0.0; + double altitude_km = altitude_m / 1000.0; + double scale_height_km; + double base_height_km; + double base_rho_kg_m3; + + // scale_height_km values: Ref "ミッション解析と軌道設計の基礎" (in Japanese) + if (altitude_km > 1000.0) { + scale_height_km = 268.0; + base_height_km = 1000.0; + base_rho_kg_m3 = 3.019E-15; + } else if (altitude_km >= 900.0 && altitude_km < 1000.0) { + scale_height_km = 181.05; + base_height_km = 900.0; + base_rho_kg_m3 = 5.245E-15; + } else if (altitude_km >= 800.0 && altitude_km < 900.0) { + scale_height_km = 124.64; + base_height_km = 800.0; + base_rho_kg_m3 = 1.170E-14; + } else if (altitude_km >= 700.0 && altitude_km < 800.0) { + scale_height_km = 88.667; + base_height_km = 700.0; + base_rho_kg_m3 = 3.614E-14; + } else if (altitude_km >= 600.0 && altitude_km < 700.0) { + scale_height_km = 71.835; + base_height_km = 600.0; + base_rho_kg_m3 = 1.454E-13; + } else if (altitude_km >= 500.0 && altitude_km < 600.0) { + scale_height_km = 63.822; + base_height_km = 500.0; + base_rho_kg_m3 = 6.967E-13; + } else if (altitude_km >= 450.0 && altitude_km < 500.0) { + scale_height_km = 60.828; + base_height_km = 450.0; + base_rho_kg_m3 = 1.585E-12; + } else if (altitude_km >= 400.0 && altitude_km < 450.0) { + scale_height_km = 58.515; + base_height_km = 400.0; + base_rho_kg_m3 = 3.725E-12; + } else if (altitude_km >= 350.0 && altitude_km < 400.0) { + scale_height_km = 53.298; + base_height_km = 350.0; + base_rho_kg_m3 = 9.158E-12; + } else if (altitude_km >= 300.0 && altitude_km < 350.0) { + scale_height_km = 53.628; + base_height_km = 300.0; + base_rho_kg_m3 = 2.418E-11; + } else if (altitude_km >= 250.0 && altitude_km < 300.0) { + scale_height_km = 45.546; + base_height_km = 250.0; + base_rho_kg_m3 = 7.248E-11; + } else if (altitude_km >= 200.0 && altitude_km < 250.0) { + scale_height_km = 37.105; + base_height_km = 200.0; + base_rho_kg_m3 = 2.789E-10; + } else if (altitude_km >= 180.0 && altitude_km < 200.0) { + scale_height_km = 29.740; + base_height_km = 180.0; + base_rho_kg_m3 = 5.464E-10; + } else if (altitude_km >= 150.0 && altitude_km < 180.0) { + scale_height_km = 22.523; + base_height_km = 150.0; + base_rho_kg_m3 = 2.070E-9; + } else if (altitude_km >= 140.0 && altitude_km < 150.0) { + scale_height_km = 16.149; + base_height_km = 140.0; + base_rho_kg_m3 = 3.845E-9; + } else if (altitude_km >= 130.0 && altitude_km < 140.0) { + scale_height_km = 12.636; + base_height_km = 130.0; + base_rho_kg_m3 = 8.484E-9; + } else if (altitude_km >= 120.0 && altitude_km < 130.0) { + scale_height_km = 9.473; + base_height_km = 120.0; + base_rho_kg_m3 = 2.438E-8; + } else if (altitude_km >= 110.0 && altitude_km < 120.0) { + scale_height_km = 7.263; + base_height_km = 110.0; + base_rho_kg_m3 = 9.661E-8; + } else if (altitude_km >= 100.0 && altitude_km < 110.0) { + scale_height_km = 5.877; + base_height_km = 100.0; + base_rho_kg_m3 = 5.297E-7; + } else if (altitude_km >= 90.0 && altitude_km < 100.0) { + scale_height_km = 5.382; + base_height_km = 90.0; + base_rho_kg_m3 = 3.396E-6; + } else if (altitude_km >= 80.0 && altitude_km < 90.0) { + scale_height_km = 5.799; + base_height_km = 80.0; + base_rho_kg_m3 = 1.905E-5; + } else if (altitude_km >= 70.0 && altitude_km < 80.0) { + scale_height_km = 6.549; + base_height_km = 70.0; + base_rho_kg_m3 = 8.770E-5; + } else if (altitude_km >= 60.0 && altitude_km < 70.0) { + scale_height_km = 7.714; + base_height_km = 60.0; + base_rho_kg_m3 = 3.206E-4; + } else if (altitude_km >= 50.0 && altitude_km < 60.0) { + scale_height_km = 8.382; + base_height_km = 50.0; + base_rho_kg_m3 = 1.057E-3; + } else if (altitude_km >= 40.0 && altitude_km < 50.0) { + scale_height_km = 7.554; + base_height_km = 40.0; + base_rho_kg_m3 = 3.972E-3; + } else if (altitude_km >= 30.0 && altitude_km < 40.0) { + scale_height_km = 6.682; + base_height_km = 30.0; + base_rho_kg_m3 = 1.774E-2; + } else if (altitude_km >= 25.0 && altitude_km < 30.0) { + scale_height_km = 6.349; + base_height_km = 25.0; + base_rho_kg_m3 = 3.899E-2; + } else if (altitude_km >= 0.0 && altitude_km < 25.0) { + scale_height_km = 7.249; + base_height_km = 0.0; + base_rho_kg_m3 = 1.225; + } else { // In case of altitude_km is minus value + scale_height_km = 7.249; + base_height_km = 0.0; + base_rho_kg_m3 = 0.0; return 0.0; } - double rho_kg_m3 = baseRho * exp(-(altitude - baseHeight) / scaleHeight); + double rho_kg_m3 = base_rho_kg_m3 * exp(-(altitude_km - base_height_km) / scale_height_km); return rho_kg_m3; } diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index 12c6c20e2..a777ab704 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -53,7 +53,7 @@ class Atmosphere : public ILoggable { * @fn GetAirDensity * @brief Return Atmospheric density [kg/m^3] */ - double GetAirDensity() const; + inline double GetAirDensity_kg_m3() const { return air_density_kg_m3_; } // Override ILoggable /** From 7e87da7354a770b16a00d4667c8099bdf5261971 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:23:43 +0100 Subject: [PATCH 0521/1086] Fix to use GeodeticPosition --- src/environment/local/atmosphere.cpp | 12 ++++++------ src/environment/local/atmosphere.hpp | 5 +++-- src/environment/local/local_environment.cpp | 2 +- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 4a5239f24..62f24d440 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -37,11 +37,11 @@ int Atmosphere::GetSpaceWeatherTable(double decimal_year, double end_time_s) { return GetSpaceWeatherTable_(decimal_year, end_time_s, initialize_file_name_, space_weather_table_); } -double Atmosphere::CalcAirDensity(double decimal_year, double end_time_s, libra::Vector<3> lat_lon_alt) { +double Atmosphere::CalcAirDensity_kg_m3(double decimal_year, double end_time_s, const GeodeticPosition position) { if (!IsCalcEnabled) return 0; if (model_ == "STANDARD") { - double altitude_m = lat_lon_alt(2); + double altitude_m = position.GetAlt_m(); air_density_kg_m3_ = CalcStandard(altitude_m); } else if (model_ == "NRLMSISE00") // NRLMSISE00 model { @@ -56,10 +56,10 @@ double Atmosphere::CalcAirDensity(double decimal_year, double end_time_s, libra: } } - double latrad = lat_lon_alt(0); - double lonrad = lat_lon_alt(1); - double alt = lat_lon_alt(2); - air_density_kg_m3_ = CalcNRLMSISE00(decimal_year, latrad, lonrad, alt, space_weather_table_, is_manual_param_used_, manual_daily_f107_, + double lat_rad = position.GetLat_rad(); + double lon_rad = position.GetLon_rad(); + double alt_m = position.GetAlt_m(); + air_density_kg_m3_ = CalcNRLMSISE00(decimal_year, lat_rad, lon_rad, alt_m, space_weather_table_, is_manual_param_used_, manual_daily_f107_, manual_average_f107_, manual_ap_); } else { // No suitable model diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index a777ab704..e6ee8a0aa 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -11,6 +11,7 @@ #include #include "library/external/nrlmsise00/wrapper_nrlmsise00.hpp" +#include "library/geodesy/geodetic_position.hpp" #include "library/logger/loggable.hpp" #include "library/math/vector.hpp" @@ -45,10 +46,10 @@ class Atmosphere : public ILoggable { * @brief Calculate atmospheric density * @param [in] decimal_year: Decimal year of simulation start [year] * @param [in] end_time_s: End time of simulation [sec] - * @param [in] lat_lon_alt: Latitude[rad], longitude[rad], and altitude[m] TODO: change to use geodetic position + * @param [in] position: Position of target point to calculate the air density * @return Atmospheric density [kg/m^3] */ - double CalcAirDensity(double decimal_year, double end_time_s, libra::Vector<3> lat_lon_alt); + double CalcAirDensity_kg_m3(double decimal_year, double end_time_s, const GeodeticPosition position); /** * @fn GetAirDensity * @brief Return Atmospheric density [kg/m^3] diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 78b1eb4c1..52736a070 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -56,7 +56,7 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend only on the position if (sim_time->GetOrbitPropagateFlag()) { srp_->UpdateAllStates(); - atmosphere_->CalcAirDensity(sim_time->GetCurrentDecimalYear(), sim_time->GetEndTime_s(), orbit.GetLatLonAlt()); + atmosphere_->CalcAirDensity_kg_m3(sim_time->GetCurrentDecimalYear(), sim_time->GetEndTime_s(), orbit.GetGeodeticPosition()); } } From 820e033cedaabf6e5c1c2e4d8feb402f83d9ea2d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:28:23 +0100 Subject: [PATCH 0522/1086] Add const for function arguments --- src/environment/local/atmosphere.cpp | 16 ++++++++-------- src/environment/local/atmosphere.hpp | 12 ++++++------ 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 62f24d440..d8f92fd7c 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -11,16 +11,16 @@ #include "library/randomization/normal_randomization.hpp" #include "library/randomization/random_walk.hpp" -Atmosphere::Atmosphere(std::string model, std::string initialize_file_name, double gauss_standard_deviation_rate, bool is_manual_param_used, - double manual_daily_f107, double manual_average_f107, double manual_ap) +Atmosphere::Atmosphere(const std::string model, const std::string initialize_file_name, const double gauss_standard_deviation_rate, + const bool is_manual_param, const double manual_f107, const double manual_f107a, const double manual_ap) : model_(model), initialize_file_name_(initialize_file_name), air_density_kg_m3_(0.0), gauss_standard_deviation_rate_(gauss_standard_deviation_rate), is_space_weather_table_imported_(false), - is_manual_param_used_(is_manual_param_used), - manual_daily_f107_(manual_daily_f107), - manual_average_f107_(manual_average_f107), + is_manual_param_used_(is_manual_param), + manual_daily_f107_(manual_f107), + manual_average_f107_(manual_f107a), manual_ap_(manual_ap) { if (model_ == "STANDARD") { std::cerr << "Air density model : STANDARD" << std::endl; @@ -37,7 +37,7 @@ int Atmosphere::GetSpaceWeatherTable(double decimal_year, double end_time_s) { return GetSpaceWeatherTable_(decimal_year, end_time_s, initialize_file_name_, space_weather_table_); } -double Atmosphere::CalcAirDensity_kg_m3(double decimal_year, double end_time_s, const GeodeticPosition position) { +double Atmosphere::CalcAirDensity_kg_m3(const double decimal_year, const double end_time_s, const GeodeticPosition position) { if (!IsCalcEnabled) return 0; if (model_ == "STANDARD") { @@ -69,7 +69,7 @@ double Atmosphere::CalcAirDensity_kg_m3(double decimal_year, double end_time_s, return AddNoise(air_density_kg_m3_); } -double Atmosphere::CalcStandard(double altitude_m) { +double Atmosphere::CalcStandard(const double altitude_m) { double altitude_km = altitude_m / 1000.0; double scale_height_km; double base_height_km; @@ -199,7 +199,7 @@ double Atmosphere::CalcStandard(double altitude_m) { return rho_kg_m3; } -double Atmosphere::AddNoise(double rho_kg_m3) { +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_, g_rand.MakeSeed()); double nrd = nr; diff --git a/src/environment/local/atmosphere.hpp b/src/environment/local/atmosphere.hpp index e6ee8a0aa..217564eac 100644 --- a/src/environment/local/atmosphere.hpp +++ b/src/environment/local/atmosphere.hpp @@ -34,8 +34,8 @@ class Atmosphere : public ILoggable { * @param [in] manual_f107a: Manual value of averaged F10.7 (3-month averaged value) * @param [in] manual_ap: Manual value of ap value */ - Atmosphere(std::string model, std::string initialize_file_name, double gauss_standard_deviation_rate, bool is_manual_param, double manual_f107, - double manual_f107a, double manual_ap); + Atmosphere(const std::string model, const std::string initialize_file_name, const double gauss_standard_deviation_rate, const bool is_manual_param, + const double manual_f107, const double manual_f107a, const double manual_ap); /** * @fn ~Atmosphere * @brief Destructor @@ -49,7 +49,7 @@ class Atmosphere : public ILoggable { * @param [in] position: Position of target point to calculate the air density * @return Atmospheric density [kg/m^3] */ - double CalcAirDensity_kg_m3(double decimal_year, double end_time_s, const GeodeticPosition position); + double CalcAirDensity_kg_m3(const double decimal_year, const double end_time_s, const GeodeticPosition position); /** * @fn GetAirDensity * @brief Return Atmospheric density [kg/m^3] @@ -93,14 +93,14 @@ class Atmosphere : public ILoggable { * @param [in] altitude_m: Altitude of spacecraft [m] * @return Atmospheric density [kg/m^3] */ - double CalcStandard(double altitude_m); + double CalcStandard(const double altitude_m); /** * @fn GetSpaceWeatherTable * @param [in] decimal_year: Decimal year of simulation start [year] * @param [in] end_time_s: End time of simulation [sec] * @return Size of table */ - int GetSpaceWeatherTable(double decimal_year, double end_time_s); + int GetSpaceWeatherTable(const double decimal_year, const double end_time_s); /** * @fn AddNoise @@ -108,7 +108,7 @@ class Atmosphere : public ILoggable { * @param [in] rho_kg_m3: True atmospheric density [kg/m^3] * @return Atmospheric density with noise [kg/m^3] */ - double AddNoise(double rho_kg_m3); + double AddNoise(const double rho_kg_m3); }; #endif // S2E_ENVIRONMENT_LOCAL_ATMOSPHERE_HPP_ From c9cdafe2339c6984bb9c075b0b191e2ebb9e2e09 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:31:34 +0100 Subject: [PATCH 0523/1086] Remove using and unused headers --- src/environment/local/geomagnetic_field.cpp | 26 +++++++++----------- src/environment/local/geomagnetic_field.hpp | 27 +++++++++------------ 2 files changed, 23 insertions(+), 30 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 47509e316..fb4654fe6 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -5,17 +5,13 @@ #include "geomagnetic_field.hpp" -#include +#include "library/external/igrf/igrf.h" +#include "library/initialize/initialize_file_access.hpp" +#include "library/randomization/global_randomization.hpp" +#include "library/randomization/normal_randomization.hpp" +#include "library/randomization/random_walk.hpp" -#include -#include -#include -#include - -using libra::NormalRand; -using namespace std; - -MagEnvironment::MagEnvironment(string fname, double mag_rwdev, double mag_rwlimit, double mag_wnvar) +MagEnvironment::MagEnvironment(std::string fname, double mag_rwdev, double mag_rwlimit, double mag_wnvar) : mag_rwdev_(mag_rwdev), mag_rwlimit_(mag_rwlimit), mag_wnvar_(mag_wnvar), fname_(fname) { for (int i = 0; i < 3; ++i) { Mag_i_[i] = 0; @@ -46,7 +42,7 @@ void MagEnvironment::AddNoise(double* mag_i_array) { static Vector<3> stddev(mag_rwdev_); static Vector<3> limit(mag_rwlimit_); static RandomWalk<3> rw(0.1, stddev, limit); - static NormalRand nr(0.0, mag_wnvar_, g_rand.MakeSeed()); + static libra::NormalRand nr(0.0, mag_wnvar_, g_rand.MakeSeed()); for (int i = 0; i < 3; ++i) { mag_i_array[i] += rw[i] + nr; } @@ -57,8 +53,8 @@ Vector<3> MagEnvironment::GetMag_i() const { return Mag_i_; } Vector<3> MagEnvironment::GetMag_b() const { return Mag_b_; } -string MagEnvironment::GetLogHeader() const { - string str_tmp = ""; +std::string MagEnvironment::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteVector("geomagnetic_field_at_spacecraft_position", "i", "nT", 3); str_tmp += WriteVector("geomagnetic_field_at_spacecraft_position", "b", "nT", 3); @@ -66,8 +62,8 @@ string MagEnvironment::GetLogHeader() const { return str_tmp; } -string MagEnvironment::GetLogValue() const { - string str_tmp = ""; +std::string MagEnvironment::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteVector(Mag_i_); str_tmp += WriteVector(Mag_b_); diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 40fbed094..833eb92e5 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -6,12 +6,9 @@ #ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ #define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ -#include -using libra::Vector; -#include -using libra::Quaternion; - -#include +#include "library/logger/loggable.hpp" +#include "library/math/quaternion.hpp" +#include "library/math/vector.hpp" /** * @class MagEnvironment @@ -44,18 +41,18 @@ class MagEnvironment : public ILoggable { * @param [in] lat_lon_alt: Latitude [rad], longitude [rad], and altitude [m] * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void CalcMag(double decyear, double side, Vector<3> lat_lon_alt, Quaternion q_i2b); + void CalcMag(double decyear, double side, libra::Vector<3> lat_lon_alt, libra::Quaternion q_i2b); /** * @fn GetMag_i * @brief Return magnetic field vector in the inertial frame [nT] */ - Vector<3> GetMag_i() const; + libra::Vector<3> GetMag_i() const; /** * @fn GetMag_b * @brief Return magnetic field vector in the body fixed frame [nT] */ - Vector<3> GetMag_b() const; + libra::Vector<3> GetMag_b() const; // Override ILoggable /** @@ -70,12 +67,12 @@ class MagEnvironment : public ILoggable { virtual std::string GetLogValue() const; private: - Vector<3> Mag_i_; //!< Magnetic field vector at the inertial frame - Vector<3> Mag_b_; //!< Magnetic field vector at the spacecraft body fixed frame - double mag_rwdev_; //!< Standard deviation of Random Walk [nT] - double mag_rwlimit_; //!< Limit of Random Walk [nT] - double mag_wnvar_; //!< Standard deviation of white noise [nT] - std::string fname_; //!< Path to the initialize file + libra::Vector<3> Mag_i_; //!< Magnetic field vector at the inertial frame + libra::Vector<3> Mag_b_; //!< Magnetic field vector at the spacecraft body fixed frame + double mag_rwdev_; //!< Standard deviation of Random Walk [nT] + double mag_rwlimit_; //!< Limit of Random Walk [nT] + double mag_wnvar_; //!< Standard deviation of white noise [nT] + std::string fname_; //!< Path to the initialize file /** * @fn AddNoise From 79822284138f8105e34c2983316da77b988ff796 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:38:13 +0100 Subject: [PATCH 0524/1086] Fix private variables --- src/environment/local/geomagnetic_field.cpp | 32 ++++++++++++--------- src/environment/local/geomagnetic_field.hpp | 23 ++++++++------- 2 files changed, 30 insertions(+), 25 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index fb4654fe6..bef76e200 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -11,15 +11,19 @@ #include "library/randomization/normal_randomization.hpp" #include "library/randomization/random_walk.hpp" -MagEnvironment::MagEnvironment(std::string fname, double mag_rwdev, double mag_rwlimit, double mag_wnvar) - : mag_rwdev_(mag_rwdev), mag_rwlimit_(mag_rwlimit), mag_wnvar_(mag_wnvar), fname_(fname) { +MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, + double white_noise_standard_deviation_nT) + : random_walk_srandard_deviation_nT_(random_walk_srandard_deviation_nT), + random_walk_limit_nT_(random_walk_limit_nT), + white_noise_standard_deviation_nT_(white_noise_standard_deviation_nT), + igrf_file_name_(igrf_file_name) { for (int i = 0; i < 3; ++i) { - Mag_i_[i] = 0; + magnetic_field_i_nT_[i] = 0; } for (int i = 0; i < 3; ++i) { - Mag_b_[i] = 0; + magnetic_field_b_nT_[i] = 0; } - set_file_path(fname_.c_str()); + set_file_path(igrf_file_name_.c_str()); } void MagEnvironment::CalcMag(double decyear, double side, Vector<3> lat_lon_alt, Quaternion q_i2b) { @@ -33,25 +37,25 @@ void MagEnvironment::CalcMag(double decyear, double side, Vector<3> lat_lon_alt, IgrfCalc(decyear, latrad, lonrad, alt, side, mag_i_array); AddNoise(mag_i_array); for (int i = 0; i < 3; ++i) { - Mag_i_[i] = mag_i_array[i]; + magnetic_field_i_nT_[i] = mag_i_array[i]; } - Mag_b_ = q_i2b.frame_conv(Mag_i_); + magnetic_field_b_nT_ = q_i2b.frame_conv(magnetic_field_i_nT_); } void MagEnvironment::AddNoise(double* mag_i_array) { - static Vector<3> stddev(mag_rwdev_); - static Vector<3> limit(mag_rwlimit_); + static Vector<3> stddev(random_walk_srandard_deviation_nT_); + static Vector<3> limit(random_walk_limit_nT_); static RandomWalk<3> rw(0.1, stddev, limit); - static libra::NormalRand nr(0.0, mag_wnvar_, g_rand.MakeSeed()); + static libra::NormalRand nr(0.0, white_noise_standard_deviation_nT_, g_rand.MakeSeed()); for (int i = 0; i < 3; ++i) { mag_i_array[i] += rw[i] + nr; } ++rw; // Update random walk } -Vector<3> MagEnvironment::GetMag_i() const { return Mag_i_; } +Vector<3> MagEnvironment::GetMag_i() const { return magnetic_field_i_nT_; } -Vector<3> MagEnvironment::GetMag_b() const { return Mag_b_; } +Vector<3> MagEnvironment::GetMag_b() const { return magnetic_field_b_nT_; } std::string MagEnvironment::GetLogHeader() const { std::string str_tmp = ""; @@ -65,8 +69,8 @@ std::string MagEnvironment::GetLogHeader() const { std::string MagEnvironment::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(Mag_i_); - str_tmp += WriteVector(Mag_b_); + str_tmp += WriteVector(magnetic_field_i_nT_); + str_tmp += WriteVector(magnetic_field_b_nT_); return str_tmp; } diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 833eb92e5..c63bc816a 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -21,12 +21,13 @@ class MagEnvironment : public ILoggable { /** * @fn MagEnvironment * @brief Constructor - * @param [in] fname: Path to initialize file - * @param [in] mag_rwdev: Standard deviation of Random Walk [nT] - * @param [in] mag_rwlimit: Limit of Random Walk [nT] - * @param [in] mag_wnvar: Standard deviation of white noise [nT] + * @param [in] igrf_file_name: Path to initialize file + * @param [in] random_walk_srandard_deviation_nT: Standard deviation of Random Walk [nT] + * @param [in] random_walk_limit_nT: Limit of Random Walk [nT] + * @param [in] white_noise_standard_deviation_nT: Standard deviation of white noise [nT] */ - MagEnvironment(std::string fname, double mag_rwdev, double mag_rwlimit, double mag_wnvar); + MagEnvironment(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, + double white_noise_standard_deviation_nT); /** * @fn ~MagEnvironment * @brief Destructor @@ -67,12 +68,12 @@ class MagEnvironment : public ILoggable { virtual std::string GetLogValue() const; private: - libra::Vector<3> Mag_i_; //!< Magnetic field vector at the inertial frame - libra::Vector<3> Mag_b_; //!< Magnetic field vector at the spacecraft body fixed frame - double mag_rwdev_; //!< Standard deviation of Random Walk [nT] - double mag_rwlimit_; //!< Limit of Random Walk [nT] - double mag_wnvar_; //!< Standard deviation of white noise [nT] - std::string fname_; //!< Path to the initialize file + libra::Vector<3> magnetic_field_i_nT_; //!< Magnetic field vector at the inertial frame [nT] + libra::Vector<3> magnetic_field_b_nT_; //!< Magnetic field vector at the spacecraft body fixed frame [nT] + double random_walk_srandard_deviation_nT_; //!< Standard deviation of Random Walk [nT] + double random_walk_limit_nT_; //!< Limit of Random Walk [nT] + double white_noise_standard_deviation_nT_; //!< Standard deviation of white noise [nT] + std::string igrf_file_name_; //!< Path to the initialize file /** * @fn AddNoise From 63f544710b239f370f9e7a4081e2b365289e23b6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:39:22 +0100 Subject: [PATCH 0525/1086] Fix function arguments --- src/environment/local/geomagnetic_field.cpp | 6 +++--- src/environment/local/geomagnetic_field.hpp | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index bef76e200..5f810b5a7 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -26,7 +26,7 @@ MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_sr set_file_path(igrf_file_name_.c_str()); } -void MagEnvironment::CalcMag(double decyear, double side, Vector<3> lat_lon_alt, Quaternion q_i2b) { +void MagEnvironment::CalcMag(double decimal_year, double sidereal_day, Vector<3> lat_lon_alt, Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; double latrad = lat_lon_alt(0); @@ -34,12 +34,12 @@ void MagEnvironment::CalcMag(double decyear, double side, Vector<3> lat_lon_alt, double alt = lat_lon_alt(2); double mag_i_array[3]; - IgrfCalc(decyear, latrad, lonrad, alt, side, mag_i_array); + IgrfCalc(decimal_year, latrad, lonrad, alt, sidereal_day, mag_i_array); AddNoise(mag_i_array); for (int i = 0; i < 3; ++i) { magnetic_field_i_nT_[i] = mag_i_array[i]; } - magnetic_field_b_nT_ = q_i2b.frame_conv(magnetic_field_i_nT_); + magnetic_field_b_nT_ = quaternion_i2b.frame_conv(magnetic_field_i_nT_); } void MagEnvironment::AddNoise(double* mag_i_array) { diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index c63bc816a..5c1a85690 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -37,12 +37,12 @@ class MagEnvironment : public ILoggable { /** * @fn CalcMag * @brief Calculate magnetic field vector - * @param [in] decyear: Decimal year [year] - * @param [in] side: Sidereal day [day] + * @param [in] decimal_year: Decimal year [year] + * @param [in] sidereal_day: Sidereal day [day] * @param [in] lat_lon_alt: Latitude [rad], longitude [rad], and altitude [m] - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void CalcMag(double decyear, double side, libra::Vector<3> lat_lon_alt, libra::Quaternion q_i2b); + void CalcMag(double decimal_year, double sidereal_day, libra::Vector<3> lat_lon_alt, libra::Quaternion quaternion_i2b); /** * @fn GetMag_i From b6a1a1aa51afb05e483be2b05ebe841efd030124 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:40:49 +0100 Subject: [PATCH 0526/1086] Change to inline function --- src/environment/local/geomagnetic_field.cpp | 4 ---- src/environment/local/geomagnetic_field.hpp | 4 ++-- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 5f810b5a7..7025acf18 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -53,10 +53,6 @@ void MagEnvironment::AddNoise(double* mag_i_array) { ++rw; // Update random walk } -Vector<3> MagEnvironment::GetMag_i() const { return magnetic_field_i_nT_; } - -Vector<3> MagEnvironment::GetMag_b() const { return magnetic_field_b_nT_; } - std::string MagEnvironment::GetLogHeader() const { std::string str_tmp = ""; diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 5c1a85690..a115cf0b1 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -48,12 +48,12 @@ class MagEnvironment : public ILoggable { * @fn GetMag_i * @brief Return magnetic field vector in the inertial frame [nT] */ - libra::Vector<3> GetMag_i() const; + inline libra::Vector<3> GetMag_i() const { return magnetic_field_i_nT_; } /** * @fn GetMag_b * @brief Return magnetic field vector in the body fixed frame [nT] */ - libra::Vector<3> GetMag_b() const; + inline libra::Vector<3> GetMag_b() const { return magnetic_field_b_nT_; } // Override ILoggable /** From 5beb13656a7f45934500ea823f3edb5222efd142 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:46:44 +0100 Subject: [PATCH 0527/1086] Fix local function variables --- src/environment/local/geomagnetic_field.cpp | 38 ++++++++++----------- src/environment/local/geomagnetic_field.hpp | 6 ++-- 2 files changed, 21 insertions(+), 23 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 7025acf18..63e65d13c 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -13,44 +13,42 @@ MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, double white_noise_standard_deviation_nT) - : random_walk_srandard_deviation_nT_(random_walk_srandard_deviation_nT), + : magnetic_field_i_nT_(0.0), + magnetic_field_b_nT_(0.0), + random_walk_standard_deviation_nT_(random_walk_srandard_deviation_nT), random_walk_limit_nT_(random_walk_limit_nT), white_noise_standard_deviation_nT_(white_noise_standard_deviation_nT), igrf_file_name_(igrf_file_name) { - for (int i = 0; i < 3; ++i) { - magnetic_field_i_nT_[i] = 0; - } - for (int i = 0; i < 3; ++i) { - magnetic_field_b_nT_[i] = 0; - } set_file_path(igrf_file_name_.c_str()); } void MagEnvironment::CalcMag(double decimal_year, double sidereal_day, Vector<3> lat_lon_alt, Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; - double latrad = lat_lon_alt(0); - double lonrad = lat_lon_alt(1); - double alt = lat_lon_alt(2); + double lat_rad = lat_lon_alt(0); + double lon_rad = lat_lon_alt(1); + double alt_m = lat_lon_alt(2); - double mag_i_array[3]; - IgrfCalc(decimal_year, latrad, lonrad, alt, sidereal_day, mag_i_array); - AddNoise(mag_i_array); + double magnetic_field_array_i_nT[3]; + IgrfCalc(decimal_year, lat_rad, lon_rad, alt_m, sidereal_day, magnetic_field_array_i_nT); + AddNoise(magnetic_field_array_i_nT); for (int i = 0; i < 3; ++i) { - magnetic_field_i_nT_[i] = mag_i_array[i]; + magnetic_field_i_nT_[i] = magnetic_field_array_i_nT[i]; } magnetic_field_b_nT_ = quaternion_i2b.frame_conv(magnetic_field_i_nT_); } -void MagEnvironment::AddNoise(double* mag_i_array) { - static Vector<3> stddev(random_walk_srandard_deviation_nT_); +void MagEnvironment::AddNoise(double* magnetic_field_array_i_nT) { + static Vector<3> standard_deviation(random_walk_standard_deviation_nT_); static Vector<3> limit(random_walk_limit_nT_); - static RandomWalk<3> rw(0.1, stddev, limit); - static libra::NormalRand nr(0.0, white_noise_standard_deviation_nT_, g_rand.MakeSeed()); + static RandomWalk<3> random_walk(0.1, standard_deviation, limit); + + static libra::NormalRand white_noise(0.0, white_noise_standard_deviation_nT_, g_rand.MakeSeed()); + for (int i = 0; i < 3; ++i) { - mag_i_array[i] += rw[i] + nr; + magnetic_field_array_i_nT[i] += random_walk[i] + white_noise; } - ++rw; // Update random walk + ++random_walk; // Update random walk } std::string MagEnvironment::GetLogHeader() const { diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index a115cf0b1..077bb3509 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -70,7 +70,7 @@ class MagEnvironment : public ILoggable { private: libra::Vector<3> magnetic_field_i_nT_; //!< Magnetic field vector at the inertial frame [nT] libra::Vector<3> magnetic_field_b_nT_; //!< Magnetic field vector at the spacecraft body fixed frame [nT] - double random_walk_srandard_deviation_nT_; //!< Standard deviation of Random Walk [nT] + double random_walk_standard_deviation_nT_; //!< Standard deviation of Random Walk [nT] double random_walk_limit_nT_; //!< Limit of Random Walk [nT] double white_noise_standard_deviation_nT_; //!< Standard deviation of white noise [nT] std::string igrf_file_name_; //!< Path to the initialize file @@ -78,9 +78,9 @@ class MagEnvironment : public ILoggable { /** * @fn AddNoise * @brief Add magnetic field noise - * @param [in/out] mag_i_array: input true magnetic field, output magnetic field with noise + * @param [in/out] magnetic_field_array_i_nT: input true magnetic field, output magnetic field with noise */ - void AddNoise(double* mag_i_array); + void AddNoise(double* magnetic_field_array_i_nT); }; #endif // S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ From 59a1602481fd5e6df850fc7f39ab8868dd2c8b72 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:50:36 +0100 Subject: [PATCH 0528/1086] fix public function name --- src/components/real/aocs/magnetometer.cpp | 4 ++-- src/components/real/aocs/magnetorquer.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/environment/local/geomagnetic_field.hpp | 12 ++++++------ src/environment/local/local_environment.cpp | 3 ++- 6 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index f239eac5d..088d3f55b 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -17,8 +17,8 @@ MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = q_b2c_.frame_conv(magnet_->GetMag_b()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + mag_c_ = q_b2c_.frame_conv(magnet_->GetMagneticField_b_nT()); // Convert frame + mag_c_ = Measure(mag_c_); // Add noises } std::string MagSensor::GetLogHeader() const { diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 4b407337d..a38d07806 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -74,7 +74,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { // Frame conversion component to body mag_moment_b_ = q_c2b_.frame_conv(mag_moment_c_); // Calc magnetic torque [Nm] - torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetMag_b()); + torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetMagneticField_b_nT()); // Update Random Walk ++n_rw_c_; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 942d69bf1..632d06fa5 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -26,7 +26,7 @@ Vector<3> MagDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) void MagDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - CalcTorque_b_Nm(local_environment.GetMag().GetMag_b()); + CalcTorque_b_Nm(local_environment.GetMag().GetMagneticField_b_nT()); } void MagDisturbance::CalcRMM() { diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 63e65d13c..81cf64706 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -22,7 +22,7 @@ MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_sr set_file_path(igrf_file_name_.c_str()); } -void MagEnvironment::CalcMag(double decimal_year, double sidereal_day, Vector<3> lat_lon_alt, Quaternion quaternion_i2b) { +void MagEnvironment::CalcMagneticField(double decimal_year, double sidereal_day, Vector<3> lat_lon_alt, Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; double lat_rad = lat_lon_alt(0); diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 077bb3509..b829c2d7e 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -35,25 +35,25 @@ class MagEnvironment : public ILoggable { virtual ~MagEnvironment() {} /** - * @fn CalcMag + * @fn CalcMagneticField * @brief Calculate magnetic field vector * @param [in] decimal_year: Decimal year [year] * @param [in] sidereal_day: Sidereal day [day] * @param [in] lat_lon_alt: Latitude [rad], longitude [rad], and altitude [m] * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void CalcMag(double decimal_year, double sidereal_day, libra::Vector<3> lat_lon_alt, libra::Quaternion quaternion_i2b); + void CalcMagneticField(double decimal_year, double sidereal_day, libra::Vector<3> lat_lon_alt, libra::Quaternion quaternion_i2b); /** - * @fn GetMag_i + * @fn GetMagneticField_i_nT * @brief Return magnetic field vector in the inertial frame [nT] */ - inline libra::Vector<3> GetMag_i() const { return magnetic_field_i_nT_; } + inline libra::Vector<3> GetMagneticField_i_nT() const { return magnetic_field_i_nT_; } /** - * @fn GetMag_b + * @fn GetMagneticField_b_nT * @brief Return magnetic field vector in the body fixed frame [nT] */ - inline libra::Vector<3> GetMag_b() const { return magnetic_field_b_nT_; } + inline libra::Vector<3> GetMagneticField_b_nT() const { return magnetic_field_b_nT_; } // Override ILoggable /** diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 52736a070..aeb293c42 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -50,7 +50,8 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { celes_info_->UpdateAllObjectsInfo(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); - mag_->CalcMag(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetLatLonAlt(), attitude.GetQuaternion_i2b()); + mag_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetLatLonAlt(), + attitude.GetQuaternion_i2b()); } // Update local environments that depend only on the position From e63c414a07855797fbce16cbe0517bc12799e54f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:54:02 +0100 Subject: [PATCH 0529/1086] Fix to use GeodeticPosition --- src/environment/local/geomagnetic_field.cpp | 8 ++++---- src/environment/local/geomagnetic_field.hpp | 5 +++-- src/environment/local/local_environment.cpp | 2 +- 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 81cf64706..1797059db 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -22,12 +22,12 @@ MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_sr set_file_path(igrf_file_name_.c_str()); } -void MagEnvironment::CalcMagneticField(double decimal_year, double sidereal_day, Vector<3> lat_lon_alt, Quaternion quaternion_i2b) { +void MagEnvironment::CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; - double lat_rad = lat_lon_alt(0); - double lon_rad = lat_lon_alt(1); - double alt_m = lat_lon_alt(2); + const double lat_rad = position.GetLat_rad(); + const double lon_rad = position.GetLon_rad(); + const double alt_m = position.GetAlt_m(); double magnetic_field_array_i_nT[3]; IgrfCalc(decimal_year, lat_rad, lon_rad, alt_m, sidereal_day, magnetic_field_array_i_nT); diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index b829c2d7e..81a1c7530 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -6,6 +6,7 @@ #ifndef S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ #define S2E_ENVIRONMENT_LOCAL_GEOMAGNETIC_FIELD_HPP_ +#include "library/geodesy/geodetic_position.hpp" #include "library/logger/loggable.hpp" #include "library/math/quaternion.hpp" #include "library/math/vector.hpp" @@ -39,10 +40,10 @@ class MagEnvironment : public ILoggable { * @brief Calculate magnetic field vector * @param [in] decimal_year: Decimal year [year] * @param [in] sidereal_day: Sidereal day [day] - * @param [in] lat_lon_alt: Latitude [rad], longitude [rad], and altitude [m] + * @param [in] position: Position of target point to calculate the magnetic field * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void CalcMagneticField(double decimal_year, double sidereal_day, libra::Vector<3> lat_lon_alt, libra::Quaternion quaternion_i2b); + void CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, libra::Quaternion quaternion_i2b); /** * @fn GetMagneticField_i_nT diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index aeb293c42..d7336bb80 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -50,7 +50,7 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { celes_info_->UpdateAllObjectsInfo(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); - mag_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetLatLonAlt(), + mag_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), attitude.GetQuaternion_i2b()); } From ad846bbcacb22d1814bad90f925d344012726600 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:56:38 +0100 Subject: [PATCH 0530/1086] Rename MagEnvironment to GeomagneticField --- .../real/aocs/initialize_magnetometer.cpp | 4 ++-- .../real/aocs/initialize_magnetometer.hpp | 4 ++-- .../real/aocs/initialize_magnetorquer.cpp | 4 ++-- .../real/aocs/initialize_magnetorquer.hpp | 5 +++-- src/components/real/aocs/magnetometer.cpp | 4 ++-- src/components/real/aocs/magnetometer.hpp | 6 +++--- src/components/real/aocs/magnetorquer.cpp | 4 ++-- src/components/real/aocs/magnetorquer.hpp | 6 +++--- src/environment/local/geomagnetic_field.cpp | 12 ++++++------ src/environment/local/geomagnetic_field.hpp | 14 +++++++------- .../local/initialize_local_environment.cpp | 4 ++-- .../local/initialize_local_environment.hpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/environment/local/local_environment.hpp | 6 +++--- 14 files changed, 39 insertions(+), 38 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index f31fe38a1..64aff1006 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,7 +7,7 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet) { +MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -27,7 +27,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str } MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const MagEnvironment* magnet) { + const GeomagneticField* magnet) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 2c6953855..45cf740ee 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -17,7 +17,7 @@ * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const MagEnvironment* magnet); +MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet); /** * @fn InitMagSensor * @brief Initialize functions for magnetometer with power port @@ -29,6 +29,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str * @param [in] mgnet: Geomegnetic environment */ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const MagEnvironment* magnet); + const GeomagneticField* magnet); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 4ffd6b076..d6b42b4e5 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -7,7 +7,7 @@ #include "library/initialize/initialize_file_access.hpp" MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, - const MagEnvironment* mag_env) { + const GeomagneticField* mag_env) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -51,7 +51,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: } MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const MagEnvironment* mag_env) { + const GeomagneticField* mag_env) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index 548463f55..fcc319d06 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -17,7 +17,8 @@ * @param [in] compo_step_time: Component step time [sec] * @param [in] mag_env: Geomegnetic environment */ -MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, const MagEnvironment* mag_env); +MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, + const GeomagneticField* mag_env); /** * @fn InitMagTorquer * @brief Initialize functions for magnetometer with power port @@ -29,6 +30,6 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: * @param [in] mag_env: Geomegnetic environment */ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const MagEnvironment* mag_env); + const GeomagneticField* mag_env); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 088d3f55b..24cdc11ab 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -7,10 +7,10 @@ #include MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, - const MagEnvironment* magnet) + const GeomagneticField* magnet) : ComponentBase(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, - const Quaternion& q_b2c, const MagEnvironment* magnet) + const Quaternion& q_b2c, const GeomagneticField* magnet) : ComponentBase(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index d5bdcb080..eef494fd9 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -32,7 +32,7 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg * @param [in] magnet: Geomagnetic environment */ MagSensor(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, - const MagEnvironment* magnet); + const GeomagneticField* magnet); /** * @fn MagSensor * @brief Constructor with power port @@ -45,7 +45,7 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg * @param [in] magnet: Geomagnetic environment */ MagSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, - const libra::Quaternion& q_b2c, const MagEnvironment* magnet); + const libra::Quaternion& q_b2c, const GeomagneticField* magnet); /** * @fn ~MagSensor * @brief Destructor @@ -82,7 +82,7 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg int sensor_id_ = 0; //!< Sensor ID libra::Quaternion q_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame - const MagEnvironment* magnet_; //!< Geomagnetic environment + const GeomagneticField* magnet_; //!< Geomagnetic environment }; #endif // S2E_COMPONENTS_REAL_AOCS_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index a38d07806..bbe15c1d1 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -13,7 +13,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const MagEnvironment* mag_env) + const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : ComponentBase(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), @@ -32,7 +32,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const MagEnvironment* mag_env) + const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : ComponentBase(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index cde36655a..ef66997a4 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -44,7 +44,7 @@ class MagTorquer : public ComponentBase, public ILoggable { MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const MagEnvironment* mag_env); + const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); /** * @fn MagTorquer * @brief Constructor with power port @@ -66,7 +66,7 @@ class MagTorquer : public ComponentBase, public ILoggable { MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const MagEnvironment* mag_env); + const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); // Override functions for ComponentBase /** @@ -124,7 +124,7 @@ class MagTorquer : public ComponentBase, public ILoggable { RandomWalk n_rw_c_; //!< Random walk noise libra::NormalRand nrs_c_[kMtqDim]; //!< Normal random noise - const MagEnvironment* mag_env_; //!< Geomagnetic environment + const GeomagneticField* mag_env_; //!< Geomagnetic environment /** * @fn CalcOutputTorque diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 1797059db..3cdaec5b6 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -11,8 +11,8 @@ #include "library/randomization/normal_randomization.hpp" #include "library/randomization/random_walk.hpp" -MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, - double white_noise_standard_deviation_nT) +GeomagneticField::GeomagneticField(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, + double white_noise_standard_deviation_nT) : magnetic_field_i_nT_(0.0), magnetic_field_b_nT_(0.0), random_walk_standard_deviation_nT_(random_walk_srandard_deviation_nT), @@ -22,7 +22,7 @@ MagEnvironment::MagEnvironment(std::string igrf_file_name, double random_walk_sr set_file_path(igrf_file_name_.c_str()); } -void MagEnvironment::CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, Quaternion quaternion_i2b) { +void GeomagneticField::CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; const double lat_rad = position.GetLat_rad(); @@ -38,7 +38,7 @@ void MagEnvironment::CalcMagneticField(double decimal_year, double sidereal_day, magnetic_field_b_nT_ = quaternion_i2b.frame_conv(magnetic_field_i_nT_); } -void MagEnvironment::AddNoise(double* magnetic_field_array_i_nT) { +void GeomagneticField::AddNoise(double* magnetic_field_array_i_nT) { static Vector<3> standard_deviation(random_walk_standard_deviation_nT_); static Vector<3> limit(random_walk_limit_nT_); static RandomWalk<3> random_walk(0.1, standard_deviation, limit); @@ -51,7 +51,7 @@ void MagEnvironment::AddNoise(double* magnetic_field_array_i_nT) { ++random_walk; // Update random walk } -std::string MagEnvironment::GetLogHeader() const { +std::string GeomagneticField::GetLogHeader() const { std::string str_tmp = ""; str_tmp += WriteVector("geomagnetic_field_at_spacecraft_position", "i", "nT", 3); @@ -60,7 +60,7 @@ std::string MagEnvironment::GetLogHeader() const { return str_tmp; } -std::string MagEnvironment::GetLogValue() const { +std::string GeomagneticField::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(magnetic_field_i_nT_); diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 81a1c7530..0c73d565b 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -12,28 +12,28 @@ #include "library/math/vector.hpp" /** - * @class MagEnvironment + * @class GeomagneticField * @brief Class to calculate magnetic field of the earth */ -class MagEnvironment : public ILoggable { +class GeomagneticField : public ILoggable { public: bool IsCalcEnabled = true; //!< Calculation flag /** - * @fn MagEnvironment + * @fn GeomagneticField * @brief Constructor * @param [in] igrf_file_name: Path to initialize file * @param [in] random_walk_srandard_deviation_nT: Standard deviation of Random Walk [nT] * @param [in] random_walk_limit_nT: Limit of Random Walk [nT] * @param [in] white_noise_standard_deviation_nT: Standard deviation of white noise [nT] */ - MagEnvironment(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, - double white_noise_standard_deviation_nT); + GeomagneticField(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, + double white_noise_standard_deviation_nT); /** - * @fn ~MagEnvironment + * @fn ~GeomagneticField * @brief Destructor */ - virtual ~MagEnvironment() {} + virtual ~GeomagneticField() {} /** * @fn CalcMagneticField diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 2ac79f67c..d573514f7 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -11,7 +11,7 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -MagEnvironment InitMagEnvironment(std::string ini_path) { +GeomagneticField InitMagEnvironment(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "MAGNETIC_FIELD_ENVIRONMENT"; @@ -20,7 +20,7 @@ MagEnvironment InitMagEnvironment(std::string ini_path) { double mag_rwlimit = conf.ReadDouble(section, "magnetic_field_random_walk_limit_nT"); double mag_wnvar = conf.ReadDouble(section, "magnetic_field_white_noise_standard_deviation_nT"); - MagEnvironment mag_env(fname, mag_rwdev, mag_rwlimit, mag_wnvar); + GeomagneticField mag_env(fname, mag_rwdev, mag_rwlimit, mag_wnvar); mag_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); mag_env.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index ee9ac6b73..bc3e26d89 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -15,7 +15,7 @@ * @brief Initialize magnetic field of the earth * @param [in] ini_path: Path to initialize file */ -MagEnvironment InitMagEnvironment(std::string ini_path); +GeomagneticField InitMagEnvironment(std::string ini_path); /** * @fn InitSRPEnvironment * @brief Initialize solar radiation pressure diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index d7336bb80..1b9330913 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -28,7 +28,7 @@ void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvi // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize - mag_ = new MagEnvironment(InitMagEnvironment(ini_fname)); + mag_ = new GeomagneticField(InitMagEnvironment(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); celes_info_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); srp_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celes_info_)); diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 271e4ee87..56afdfdf2 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -67,9 +67,9 @@ class LocalEnvironment { inline const Atmosphere& GetAtmosphere() const { return *atmosphere_; } /** * @fn GetMag - * @brief Return MagEnvironment class + * @brief Return GeomagneticField class */ - inline const MagEnvironment& GetMag() const { return *mag_; } + inline const GeomagneticField& GetMag() const { return *mag_; } /** * @fn GetSrp * @brief Return SRPEnvironment class @@ -83,7 +83,7 @@ class LocalEnvironment { private: Atmosphere* atmosphere_; //!< Atmospheric density of the earth - MagEnvironment* mag_; //!< Magnetic field of the earth + GeomagneticField* mag_; //!< Magnetic field of the earth SRPEnvironment* srp_; //!< Solar radiation pressure LocalCelestialInformation* celes_info_; //!< Celestial information }; From 68f873a5913348d9472172ed33dfff24ab30b0ba Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 13:57:21 +0100 Subject: [PATCH 0531/1086] Rename MagEnvironment to GeomagneticField --- src/environment/local/initialize_local_environment.cpp | 2 +- src/environment/local/initialize_local_environment.hpp | 4 ++-- src/environment/local/local_environment.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index d573514f7..f53007969 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -11,7 +11,7 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -GeomagneticField InitMagEnvironment(std::string ini_path) { +GeomagneticField InitGeomagneticField(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "MAGNETIC_FIELD_ENVIRONMENT"; diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index bc3e26d89..59ad348fa 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -11,11 +11,11 @@ #include /** - * @fn InitMagEnvironment + * @fn InitGeomagneticField * @brief Initialize magnetic field of the earth * @param [in] ini_path: Path to initialize file */ -GeomagneticField InitMagEnvironment(std::string ini_path); +GeomagneticField InitGeomagneticField(std::string ini_path); /** * @fn InitSRPEnvironment * @brief Initialize solar radiation pressure diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 1b9330913..c26a69235 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -28,7 +28,7 @@ void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvi // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize - mag_ = new GeomagneticField(InitMagEnvironment(ini_fname)); + mag_ = new GeomagneticField(InitGeomagneticField(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); celes_info_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); srp_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celes_info_)); From e77a993e62ef7d7a684ace59cdf1442ff3685708 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:00:02 +0100 Subject: [PATCH 0532/1086] fix function argument name --- .../local/initialize_local_environment.cpp | 14 ++++++------- .../local/initialize_local_environment.hpp | 20 +++++++++---------- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index f53007969..b7f986c26 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -11,8 +11,8 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -GeomagneticField InitGeomagneticField(std::string ini_path) { - auto conf = IniAccess(ini_path); +GeomagneticField InitGeomagneticField(std::string initialize_file_path) { + auto conf = IniAccess(initialize_file_path); const char* section = "MAGNETIC_FIELD_ENVIRONMENT"; std::string fname = conf.ReadString(section, "coefficient_file"); @@ -27,19 +27,19 @@ GeomagneticField InitGeomagneticField(std::string ini_path) { return mag_env; } -SRPEnvironment InitSRPEnvironment(std::string ini_path, LocalCelestialInformation* local_celes_info) { - auto conf = IniAccess(ini_path); +SRPEnvironment InitSRPEnvironment(std::string initialize_file_path, LocalCelestialInformation* local_celestial_information) { + auto conf = IniAccess(initialize_file_path); const char* section = "SOLAR_RADIATION_PRESSURE_ENVIRONMENT"; - SRPEnvironment srp_env(local_celes_info); + SRPEnvironment srp_env(local_celestial_information); srp_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); srp_env.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return srp_env; } -Atmosphere InitAtmosphere(std::string ini_path) { - auto conf = IniAccess(ini_path); +Atmosphere InitAtmosphere(std::string initialize_file_path) { + auto conf = IniAccess(initialize_file_path); const char* section = "ATMOSPHERE"; double f107_threshold = 50.0; double f107_default = 150.0; diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index 59ad348fa..f18a8883e 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -6,28 +6,28 @@ #ifndef S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ -#include -#include -#include +#include "atmosphere.hpp" +#include "geomagnetic_field.hpp" +#include "solar_radiation_pressure_environment.hpp" /** * @fn InitGeomagneticField * @brief Initialize magnetic field of the earth - * @param [in] ini_path: Path to initialize file + * @param [in] initialize_file_path: Path to initialize file */ -GeomagneticField InitGeomagneticField(std::string ini_path); +GeomagneticField InitGeomagneticField(std::string initialize_file_path); /** * @fn InitSRPEnvironment * @brief Initialize solar radiation pressure - * @param [in] ini_path: Path to initialize file - * @param [in] local_celes_info: Local celestial information + * @param [in] initialize_file_path: Path to initialize file + * @param [in] local_celestial_information: Local celestial information */ -SRPEnvironment InitSRPEnvironment(std::string ini_path, LocalCelestialInformation* local_celes_info); +SRPEnvironment InitSRPEnvironment(std::string initialize_file_path, LocalCelestialInformation* local_celestial_information); /** * @fn InitAtmosphere * @brief Initialize atmospheric density of the earth - * @param [in] ini_path: Path to initialize file + * @param [in] initialize_file_path: Path to initialize file */ -Atmosphere InitAtmosphere(std::string ini_path); +Atmosphere InitAtmosphere(std::string initialize_file_path); #endif // S2E_ENVIRONMENT_LOCAL_INITIALIZE_LOCAL_ENVIRONMENT_HPP_ From 2175882a31654992fc8da59a848ee50294b940a8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:02:35 +0100 Subject: [PATCH 0533/1086] Change to const for function arguments --- src/environment/local/geomagnetic_field.cpp | 7 ++++--- src/environment/local/geomagnetic_field.hpp | 7 ++++--- src/library/math/quaternion.cpp | 4 ++-- src/library/math/quaternion.hpp | 4 ++-- 4 files changed, 12 insertions(+), 10 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 3cdaec5b6..5aec7f26c 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -11,8 +11,8 @@ #include "library/randomization/normal_randomization.hpp" #include "library/randomization/random_walk.hpp" -GeomagneticField::GeomagneticField(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, - double white_noise_standard_deviation_nT) +GeomagneticField::GeomagneticField(const std::string igrf_file_name, const double random_walk_srandard_deviation_nT, + const double random_walk_limit_nT, const double white_noise_standard_deviation_nT) : magnetic_field_i_nT_(0.0), magnetic_field_b_nT_(0.0), random_walk_standard_deviation_nT_(random_walk_srandard_deviation_nT), @@ -22,7 +22,8 @@ GeomagneticField::GeomagneticField(std::string igrf_file_name, double random_wal set_file_path(igrf_file_name_.c_str()); } -void GeomagneticField::CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, Quaternion quaternion_i2b) { +void GeomagneticField::CalcMagneticField(const double decimal_year, const double sidereal_day, const GeodeticPosition position, + const Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; const double lat_rad = position.GetLat_rad(); diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 0c73d565b..9e3a38402 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -27,8 +27,8 @@ class GeomagneticField : public ILoggable { * @param [in] random_walk_limit_nT: Limit of Random Walk [nT] * @param [in] white_noise_standard_deviation_nT: Standard deviation of white noise [nT] */ - GeomagneticField(std::string igrf_file_name, double random_walk_srandard_deviation_nT, double random_walk_limit_nT, - double white_noise_standard_deviation_nT); + GeomagneticField(const std::string igrf_file_name, const double random_walk_srandard_deviation_nT, const double random_walk_limit_nT, + const double white_noise_standard_deviation_nT); /** * @fn ~GeomagneticField * @brief Destructor @@ -43,7 +43,8 @@ class GeomagneticField : public ILoggable { * @param [in] position: Position of target point to calculate the magnetic field * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void CalcMagneticField(double decimal_year, double sidereal_day, const GeodeticPosition position, libra::Quaternion quaternion_i2b); + void CalcMagneticField(const double decimal_year, const double sidereal_day, const GeodeticPosition position, + const libra::Quaternion quaternion_i2b); /** * @fn GetMagneticField_i_nT diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 345132115..0d1ebbcb4 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -212,7 +212,7 @@ Quaternion Quaternion::fromEuler(Vector<3> euler) { return Quaternion::fromDCM(dcm); } -Vector<3> Quaternion::frame_conv(const Vector<3>& v) { +Vector<3> Quaternion::frame_conv(const Vector<3>& v) const { Quaternion conj = conjugate(); Quaternion temp1 = conj * v; Quaternion temp2 = temp1 * q_; @@ -223,7 +223,7 @@ Vector<3> Quaternion::frame_conv(const Vector<3>& v) { return ans; } -Vector<3> Quaternion::frame_conv_inv(const Vector<3>& cv) { +Vector<3> Quaternion::frame_conv_inv(const Vector<3>& cv) const { Quaternion conj = conjugate(); Quaternion temp1 = q_ * cv; Quaternion temp2 = temp1 * conj; diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 79aa26106..4bb5334f3 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -140,7 +140,7 @@ class Quaternion { * @param [in] cv: Target vector * @return Converted vector */ - Vector<3> frame_conv(const Vector<3>& cv); + Vector<3> frame_conv(const Vector<3>& cv) const; /** * @fn frame_conv_inv @@ -148,7 +148,7 @@ class Quaternion { * @param [in] cv: Target vector * @return Converted vector */ - Vector<3> frame_conv_inv(const Vector<3>& cv); + Vector<3> frame_conv_inv(const Vector<3>& cv) const; /** * @fn toVector From 39dbe5b2823b9cc85301413bc8646de7d2e0ddd8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:13:02 +0100 Subject: [PATCH 0534/1086] Fix private members name --- .../local/local_celestial_information.cpp | 144 +++++++++--------- .../local/local_celestial_information.hpp | 38 ++--- 2 files changed, 91 insertions(+), 91 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 6300f187f..0818856fd 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -9,49 +9,49 @@ #include #include -#include #include -using namespace std; +#include "library/logger/log_utility.hpp" -LocalCelestialInformation::LocalCelestialInformation(const CelestialInformation* glo_celes_info) : glo_celes_info_(glo_celes_info) { - int num_of_state = glo_celes_info_->GetNumberOfSelectedBodies() * 3; - celes_objects_pos_from_center_b_ = new double[num_of_state]; - celes_objects_vel_from_center_b_ = new double[num_of_state]; - celes_objects_pos_from_sc_i_ = new double[num_of_state]; - celes_objects_vel_from_sc_i_ = new double[num_of_state]; - celes_objects_pos_from_sc_b_ = new double[num_of_state]; - celes_objects_vel_from_sc_b_ = new double[num_of_state]; +LocalCelestialInformation::LocalCelestialInformation(const CelestialInformation* global_celestial_information) + : global_celestial_information_(global_celestial_information) { + int num_of_state = global_celestial_information_->GetNumberOfSelectedBodies() * 3; + celestial_body_position_from_center_b_m_ = new double[num_of_state]; + celestial_body_velocity_from_center_b_m_s_ = new double[num_of_state]; + celestial_body_position_from_spacecraft_i_m_ = new double[num_of_state]; + celestial_body_velocity_from_spacecraft_i_m_s_ = new double[num_of_state]; + celestial_body_position_from_spacecraft_b_m_ = new double[num_of_state]; + celestial_body_velocity_from_spacecraft_b_m_s_ = new double[num_of_state]; for (int i = 0; i < num_of_state; i++) { - celes_objects_pos_from_center_b_[i] = 0.0; - celes_objects_vel_from_center_b_[i] = 0.0; - celes_objects_pos_from_sc_i_[i] = 0.0; - celes_objects_vel_from_sc_i_[i] = 0.0; - celes_objects_pos_from_sc_b_[i] = 0.0; - celes_objects_vel_from_sc_b_[i] = 0.0; + celestial_body_position_from_center_b_m_[i] = 0.0; + celestial_body_velocity_from_center_b_m_s_[i] = 0.0; + celestial_body_position_from_spacecraft_i_m_[i] = 0.0; + celestial_body_velocity_from_spacecraft_i_m_s_[i] = 0.0; + celestial_body_position_from_spacecraft_b_m_[i] = 0.0; + celestial_body_velocity_from_spacecraft_b_m_s_[i] = 0.0; } } LocalCelestialInformation::~LocalCelestialInformation() { - delete[] celes_objects_pos_from_center_b_; - delete[] celes_objects_vel_from_center_b_; - delete[] celes_objects_pos_from_sc_i_; - delete[] celes_objects_vel_from_sc_i_; - delete[] celes_objects_pos_from_sc_b_; - delete[] celes_objects_vel_from_sc_b_; + delete[] celestial_body_position_from_center_b_m_; + delete[] celestial_body_velocity_from_center_b_m_s_; + delete[] celestial_body_position_from_spacecraft_i_m_; + delete[] celestial_body_velocity_from_spacecraft_i_m_s_; + delete[] celestial_body_position_from_spacecraft_b_m_; + delete[] celestial_body_velocity_from_spacecraft_b_m_s_; } -void LocalCelestialInformation::UpdateAllObjectsInfo(const Vector<3> sc_pos_from_center_i, const Vector<3> sc_vel_from_center_i, - const Quaternion q_i2b, const Vector<3> sc_body_rate) { +void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_center_i, const libra::Vector<3> sc_vel_from_center_i, + const libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate) { Vector<3> pos_center_i, vel_center_i; - for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = glo_celes_info_->GetPositionFromCenter_i_m(i); - vel_center_i = glo_celes_info_->GetVelocityFromCenter_i_m_s(i); + for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { + pos_center_i = global_celestial_information_->GetPositionFromCenter_i_m(i); + vel_center_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); // Change origin of frame for (int j = 0; j < 3; j++) { - celes_objects_pos_from_sc_i_[i * 3 + j] = pos_center_i[j] - sc_pos_from_center_i[j]; - celes_objects_vel_from_sc_i_[i * 3 + j] = vel_center_i[j] - sc_vel_from_center_i[j]; + celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_center_i[j] - sc_pos_from_center_i[j]; + celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_center_i[j] - sc_vel_from_center_i[j]; } } CalcAllPosVel_b(q_i2b, sc_body_rate); @@ -59,18 +59,18 @@ void LocalCelestialInformation::UpdateAllObjectsInfo(const Vector<3> sc_pos_from return; } -void LocalCelestialInformation::CalcAllPosVel_b(const Quaternion q_i2b, const Vector<3> sc_body_rate) { - Vector<3> pos_center_i, vel_center_i; +void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate) { + libra::Vector<3> pos_center_i, vel_center_i; double r_buf1_i[3], v_buf1_i[3], r_buf1_b[3], v_buf1_b[3]; double r_buf2_i[3], v_buf2_i[3], r_buf2_b[3], v_buf2_b[3]; - for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = glo_celes_info_->GetPositionFromCenter_i_m(i); - vel_center_i = glo_celes_info_->GetVelocityFromCenter_i_m_s(i); + for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { + pos_center_i = global_celestial_information_->GetPositionFromCenter_i_m(i); + vel_center_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); for (int j = 0; j < 3; j++) { r_buf1_i[j] = pos_center_i[j]; - r_buf2_i[j] = celes_objects_pos_from_sc_i_[i * 3 + j]; + r_buf2_i[j] = celestial_body_position_from_spacecraft_i_m_[i * 3 + j]; v_buf1_i[j] = vel_center_i[j]; - v_buf2_i[j] = celes_objects_vel_from_sc_i_[i * 3 + j]; + v_buf2_i[j] = celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j]; } Convert_i2b(r_buf1_i, r_buf1_b, q_i2b); Convert_i2b(r_buf2_i, r_buf2_b, q_i2b); @@ -78,32 +78,32 @@ void LocalCelestialInformation::CalcAllPosVel_b(const Quaternion q_i2b, const Ve Convert_i2b_velocity(r_buf2_i, v_buf2_i, v_buf2_b, q_i2b, sc_body_rate); for (int j = 0; j < 3; j++) { - celes_objects_pos_from_center_b_[i * 3 + j] = r_buf1_b[j]; - celes_objects_pos_from_sc_b_[i * 3 + j] = r_buf2_b[j]; - celes_objects_vel_from_center_b_[i * 3 + j] = v_buf1_b[j]; - celes_objects_vel_from_sc_b_[i * 3 + j] = v_buf2_b[j]; + celestial_body_position_from_center_b_m_[i * 3 + j] = r_buf1_b[j]; + celestial_body_position_from_spacecraft_b_m_[i * 3 + j] = r_buf2_b[j]; + celestial_body_velocity_from_center_b_m_s_[i * 3 + j] = v_buf1_b[j]; + celestial_body_velocity_from_spacecraft_b_m_s_[i * 3 + j] = v_buf2_b[j]; } } } -void Convert_i2b(const double* src_i, double* dst_b, Quaternion q_i2b) { - Vector<3> temp_i; +void Convert_i2b(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { + libra::Vector<3> temp_i; for (int i = 0; i < 3; i++) { temp_i[i] = src_i[i]; } - Vector<3> temp_b = q_i2b.frame_conv(temp_i); + libra::Vector<3> temp_b = q_i2b.frame_conv(temp_i); for (int i = 0; i < 3; i++) { dst_b[i] = temp_b[i]; } } -void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, Quaternion q_i2b, const Vector<3> bodyrate_b) { +void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b) { // copy input vector - Vector<3> vi; + libra::Vector<3> vi; for (int i = 0; i < 3; i++) { vi[i] = v_i[i]; } - Vector<3> ri; + libra::Vector<3> ri; for (int i = 0; i < 3; i++) { ri[i] = r_i[i]; } @@ -115,77 +115,77 @@ void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, Qua } // compute cross term wxr - Vector<3> wxr_i = outer_product(wb, ri); + libra::Vector<3> wxr_i = outer_product(wb, ri); // compute dr/dt + wxr for (int i = 0; i < 3; i++) { vi[i] = vi[i] - wxr_i[i]; } // convert vector in inertial coordinate into that in body coordinate - Vector<3> temp_b = q_i2b.frame_conv(vi); + libra::Vector<3> temp_b = q_i2b.frame_conv(vi); for (int i = 0; i < 3; i++) { v_b[i] = temp_b[i]; } } -Vector<3> LocalCelestialInformation::GetPosFromSC_i(const char* body_name) const { - Vector<3> position; +libra::Vector<3> LocalCelestialInformation::GetPosFromSC_i(const char* body_name) const { + libra::Vector<3> position; int index = 0; - index = glo_celes_info_->CalcBodyIdFromName(body_name); + index = global_celestial_information_->CalcBodyIdFromName(body_name); for (int i = 0; i < 3; i++) { - position[i] = celes_objects_pos_from_sc_i_[index * 3 + i]; + position[i] = celestial_body_position_from_spacecraft_i_m_[index * 3 + i]; } return position; } Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_i() const { - string body_name = glo_celes_info_->GetCenterBodyName(); + std::string body_name = global_celestial_information_->GetCenterBodyName(); Vector<3> position = GetPosFromSC_i(body_name.c_str()); return position; } -Vector<3> LocalCelestialInformation::GetPosFromSC_b(const char* body_name) const { - Vector<3> position; +libra::Vector<3> LocalCelestialInformation::GetPosFromSC_b(const char* body_name) const { + libra::Vector<3> position; int index = 0; - index = glo_celes_info_->CalcBodyIdFromName(body_name); + index = global_celestial_information_->CalcBodyIdFromName(body_name); for (int i = 0; i < 3; i++) { - position[i] = celes_objects_pos_from_sc_b_[index * 3 + i]; + position[i] = celestial_body_position_from_spacecraft_b_m_[index * 3 + i]; } return position; } -Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_b(void) const { - string body_name = glo_celes_info_->GetCenterBodyName(); - Vector<3> position = GetPosFromSC_b(body_name.c_str()); +libra::Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_b(void) const { + std::string body_name = global_celestial_information_->GetCenterBodyName(); + libra::Vector<3> position = GetPosFromSC_b(body_name.c_str()); return position; } -string LocalCelestialInformation::GetLogHeader() const { +std::string LocalCelestialInformation::GetLogHeader() const { SpiceBoolean found; const int maxlen = 100; char namebuf[maxlen]; - string str_tmp = ""; - for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { - SpiceInt planet_id = glo_celes_info_->GetSelectedBodyIds()[i]; + std::string str_tmp = ""; + for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { + SpiceInt planet_id = global_celestial_information_->GetSelectedBodyIds()[i]; // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); - string name = namebuf; + std::string name = namebuf; std::transform(name.begin(), name.end(), name.begin(), ::tolower); - string body_pos = name + "_position_from_spacecraft"; - string body_vel = name + "_velocity_from_spacecraft"; + std::string body_pos = name + "_position_from_spacecraft"; + std::string body_vel = name + "_velocity_from_spacecraft"; str_tmp += WriteVector(body_pos, "b", "m", 3); str_tmp += WriteVector(body_vel, "b", "m/s", 3); } return str_tmp; } -string LocalCelestialInformation::GetLogValue() const { - string str_tmp = ""; - for (int i = 0; i < glo_celes_info_->GetNumberOfSelectedBodies(); i++) { +std::string LocalCelestialInformation::GetLogValue() const { + std::string str_tmp = ""; + for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { for (int j = 0; j < 3; j++) { - str_tmp += WriteScalar(celes_objects_pos_from_sc_b_[i * 3 + j]); + str_tmp += WriteScalar(celestial_body_position_from_spacecraft_b_m_[i * 3 + j]); } for (int j = 0; j < 3; j++) { - str_tmp += WriteScalar(celes_objects_vel_from_sc_b_[i * 3 + j]); + str_tmp += WriteScalar(celestial_body_velocity_from_spacecraft_b_m_s_[i * 3 + j]); } } return str_tmp; diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 0eacfc4af..d23d4a61b 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -17,9 +17,9 @@ class LocalCelestialInformation : public ILoggable { /** * @fn LocalCelestialInformation * @brief Constructor - * @param [in] glo_celes_info: Global celestial information + * @param [in] global_celestial_information: Global celestial information */ - LocalCelestialInformation(const CelestialInformation* glo_celes_info); + LocalCelestialInformation(const CelestialInformation* global_celestial_information); /** * @fn ~LocalCelestialInformation * @brief Destructor @@ -34,45 +34,45 @@ class LocalCelestialInformation : public ILoggable { * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void UpdateAllObjectsInfo(const Vector<3> sc_pos_from_center_i, const Vector<3> sc_vel_from_center_i, Quaternion q_i2b, - const Vector<3> sc_body_rate); + void UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_center_i, const libra::Vector<3> sc_vel_from_center_i, libra::Quaternion q_i2b, + const libra::Vector<3> sc_body_rate); /** * @fn CalcAllPosVel_b * @brief Frame conversion to the body frame for all selected celestial bodies * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void CalcAllPosVel_b(Quaternion q_i2b, const Vector<3> sc_body_rate); + void CalcAllPosVel_b(libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate); /** * @fn GetPosFromSC_i * @brief Return position of a selected body (Origin: Spacecraft, Frame: Inertial frame) * @param [in] body_name Celestial body name */ - Vector<3> GetPosFromSC_i(const char* body_name) const; + libra::Vector<3> GetPosFromSC_i(const char* body_name) const; /** * @fn GetCenterBodyPosFromSC_i * @brief Return position of the center body (Origin: Spacecraft, Frame: Inertial frame) */ - Vector<3> GetCenterBodyPosFromSC_i(void) const; + libra::Vector<3> GetCenterBodyPosFromSC_i(void) const; /** * @fn GetPosFromSC_b * @brief Return position of a selected body (Origin: Spacecraft, Frame: Body fixed frame) * @param [in] body_name Celestial body name */ - Vector<3> GetPosFromSC_b(const char* body_name) const; + libra::Vector<3> GetPosFromSC_b(const char* body_name) const; /** * @fn GetCenterBodyPosFromSC_b * @brief Return position of the center body (Origin: Spacecraft, Frame: Body fixed frame) */ - Vector<3> GetCenterBodyPosFromSC_b(void) const; + libra::Vector<3> GetCenterBodyPosFromSC_b(void) const; /** * @fn GetGlobalInfo * @brief Return global celestial information */ - inline const CelestialInformation& GetGlobalInfo() const { return *glo_celes_info_; } + inline const CelestialInformation& GetGlobalInfo() const { return *global_celestial_information_; } // Override ILoggable /** @@ -87,14 +87,14 @@ class LocalCelestialInformation : public ILoggable { virtual std::string GetLogValue() const; private: - const CelestialInformation* glo_celes_info_; //!< Global celestial information + const CelestialInformation* global_celestial_information_; //!< Global celestial information // Local Information - double* celes_objects_pos_from_sc_i_; //!< Celestial body position from spacecraft in the inertial frame [m] - double* celes_objects_vel_from_sc_i_; //!< Celestial body velocity from spacecraft in the inertial frame [m/s] - double* celes_objects_pos_from_center_b_; //!< Celestial body position from the center body in the spacecraft body fixed frame [m] - double* celes_objects_pos_from_sc_b_; //!< Celestial body position from the spacecraft in the spacecraft body fixed frame [m] - double* celes_objects_vel_from_center_b_; //!< Celestial body velocity from the center body in the spacecraft body fixed frame [m/s] - double* celes_objects_vel_from_sc_b_; //!< Celestial body velocity from the spacecraft in the spacecraft body fixed frame [m/s] + double* celestial_body_position_from_spacecraft_i_m_; //!< Celestial body position from spacecraft in the inertial frame [m] + double* celestial_body_velocity_from_spacecraft_i_m_s_; //!< Celestial body velocity from spacecraft in the inertial frame [m/s] + double* celestial_body_position_from_center_b_m_; //!< Celestial body position from the center body in the spacecraft body fixed frame [m] + double* celestial_body_position_from_spacecraft_b_m_; //!< Celestial body position from the spacecraft in the spacecraft body fixed frame [m] + double* celestial_body_velocity_from_center_b_m_s_; //!< Celestial body velocity from the center body in the spacecraft body fixed frame [m/s] + double* celestial_body_velocity_from_spacecraft_b_m_s_; //!< Celestial body velocity from the spacecraft in the spacecraft body fixed frame [m/s] }; /** @@ -104,7 +104,7 @@ class LocalCelestialInformation : public ILoggable { * @param [out] dst_b: Output vector in the body fixed frame * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ -void Convert_i2b(const double* src_i, double* dst_b, const Quaternion q_i2b); +void Convert_i2b(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); /** * @fn Convert_i2b_velocity @@ -115,6 +115,6 @@ void Convert_i2b(const double* src_i, double* dst_b, const Quaternion q_i2b); * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ -void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const Quaternion q_i2b, const Vector<3> bodyrate_b); +void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b); #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ From da29fa4d5d31056e6ec152404c536c07d4cfa8fa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:17:58 +0100 Subject: [PATCH 0535/1086] Move public function to private function --- .../local/local_celestial_information.cpp | 5 ++- .../local/local_celestial_information.hpp | 38 +++++++++---------- 2 files changed, 22 insertions(+), 21 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 0818856fd..509ab1e5c 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -86,7 +86,7 @@ void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion q_i2b, c } } -void Convert_i2b(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { +void LocalCelestialInformation::Convert_i2b(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { libra::Vector<3> temp_i; for (int i = 0; i < 3; i++) { temp_i[i] = src_i[i]; @@ -97,7 +97,8 @@ void Convert_i2b(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { } } -void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b) { +void LocalCelestialInformation::Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, + const libra::Vector<3> bodyrate_b) { // copy input vector libra::Vector<3> vi; for (int i = 0; i < 3; i++) { diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index d23d4a61b..2944947b4 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -95,26 +95,26 @@ class LocalCelestialInformation : public ILoggable { double* celestial_body_position_from_spacecraft_b_m_; //!< Celestial body position from the spacecraft in the spacecraft body fixed frame [m] double* celestial_body_velocity_from_center_b_m_s_; //!< Celestial body velocity from the center body in the spacecraft body fixed frame [m/s] double* celestial_body_velocity_from_spacecraft_b_m_s_; //!< Celestial body velocity from the spacecraft in the spacecraft body fixed frame [m/s] -}; -/** - * @fn Convert_i2b - * @brief Convert position vector in the inertial frame to the body fixed frame - * @param [in] src_i: Source vector in the inertial frame - * @param [out] dst_b: Output vector in the body fixed frame - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - */ -void Convert_i2b(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); + /** + * @fn Convert_i2b + * @brief Convert position vector in the inertial frame to the body fixed frame + * @param [in] src_i: Source vector in the inertial frame + * @param [out] dst_b: Output vector in the body fixed frame + * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + */ + void Convert_i2b(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); -/** - * @fn Convert_i2b_velocity - * @brief Convert velocity vector in the inertial frame to the body fixed frame - * @param [in] r_i: Position vector in the inertial frame - * @param [in] v_i: Velocity vector in the inertial frame - * @param [out] v_b: Output Velocity vector in the body fixed frame - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] - */ -void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b); + /** + * @fn Convert_i2b_velocity + * @brief Convert velocity vector in the inertial frame to the body fixed frame + * @param [in] r_i: Position vector in the inertial frame + * @param [in] v_i: Velocity vector in the inertial frame + * @param [out] v_b: Output Velocity vector in the body fixed frame + * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] + */ + void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b); +}; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ From 1b48877785164efce0f492601bae08bb68cd62d9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:19:36 +0100 Subject: [PATCH 0536/1086] Rename private function --- .../local/local_celestial_information.cpp | 14 +++++++------- .../local/local_celestial_information.hpp | 9 +++++---- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 509ab1e5c..015cad680 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -72,10 +72,10 @@ void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion q_i2b, c v_buf1_i[j] = vel_center_i[j]; v_buf2_i[j] = celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j]; } - Convert_i2b(r_buf1_i, r_buf1_b, q_i2b); - Convert_i2b(r_buf2_i, r_buf2_b, q_i2b); - Convert_i2b_velocity(r_buf1_i, v_buf1_i, v_buf1_b, q_i2b, sc_body_rate); - Convert_i2b_velocity(r_buf2_i, v_buf2_i, v_buf2_b, q_i2b, sc_body_rate); + ConvertInertialToBody(r_buf1_i, r_buf1_b, q_i2b); + ConvertInertialToBody(r_buf2_i, r_buf2_b, q_i2b); + ConvertVelocityInertialToBody(r_buf1_i, v_buf1_i, v_buf1_b, q_i2b, sc_body_rate); + ConvertVelocityInertialToBody(r_buf2_i, v_buf2_i, v_buf2_b, q_i2b, sc_body_rate); for (int j = 0; j < 3; j++) { celestial_body_position_from_center_b_m_[i * 3 + j] = r_buf1_b[j]; @@ -86,7 +86,7 @@ void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion q_i2b, c } } -void LocalCelestialInformation::Convert_i2b(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { +void LocalCelestialInformation::ConvertInertialToBody(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { libra::Vector<3> temp_i; for (int i = 0; i < 3; i++) { temp_i[i] = src_i[i]; @@ -97,8 +97,8 @@ void LocalCelestialInformation::Convert_i2b(const double* src_i, double* dst_b, } } -void LocalCelestialInformation::Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, - const libra::Vector<3> bodyrate_b) { +void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, + const libra::Vector<3> bodyrate_b) { // copy input vector libra::Vector<3> vi; for (int i = 0; i < 3; i++) { diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 2944947b4..a0e3a36de 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -97,16 +97,16 @@ class LocalCelestialInformation : public ILoggable { double* celestial_body_velocity_from_spacecraft_b_m_s_; //!< Celestial body velocity from the spacecraft in the spacecraft body fixed frame [m/s] /** - * @fn Convert_i2b + * @fn ConvertInertialToBody * @brief Convert position vector in the inertial frame to the body fixed frame * @param [in] src_i: Source vector in the inertial frame * @param [out] dst_b: Output vector in the body fixed frame * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void Convert_i2b(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); + void ConvertInertialToBody(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); /** - * @fn Convert_i2b_velocity + * @fn ConvertVelocityInertialToBody * @brief Convert velocity vector in the inertial frame to the body fixed frame * @param [in] r_i: Position vector in the inertial frame * @param [in] v_i: Velocity vector in the inertial frame @@ -114,7 +114,8 @@ class LocalCelestialInformation : public ILoggable { * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void Convert_i2b_velocity(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, const libra::Vector<3> bodyrate_b); + void ConvertVelocityInertialToBody(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, + const libra::Vector<3> bodyrate_b); }; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ From 7f6e04446988ecfb4e2e8a366eaf70a324ed58c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:24:26 +0100 Subject: [PATCH 0537/1086] Fic function argument name --- .../local/local_celestial_information.cpp | 73 ++++++++++--------- .../local/local_celestial_information.hpp | 36 ++++----- 2 files changed, 55 insertions(+), 54 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 015cad680..dc0bf2cee 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -42,89 +42,90 @@ LocalCelestialInformation::~LocalCelestialInformation() { delete[] celestial_body_velocity_from_spacecraft_b_m_s_; } -void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_center_i, const libra::Vector<3> sc_vel_from_center_i, - const libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate) { - Vector<3> pos_center_i, vel_center_i; +void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_centeposition_i, + const libra::Vector<3> sc_vel_from_centeposition_i, const libra::Quaternion quaternion_i2b, + const libra::Vector<3> sc_body_rate) { + Vector<3> pos_centeposition_i, vel_centeposition_i; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = global_celestial_information_->GetPositionFromCenter_i_m(i); - vel_center_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); + pos_centeposition_i = global_celestial_information_->GetPositionFromCenter_i_m(i); + vel_centeposition_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); // Change origin of frame for (int j = 0; j < 3; j++) { - celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_center_i[j] - sc_pos_from_center_i[j]; - celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_center_i[j] - sc_vel_from_center_i[j]; + celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_centeposition_i[j] - sc_pos_from_centeposition_i[j]; + celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_centeposition_i[j] - sc_vel_from_centeposition_i[j]; } } - CalcAllPosVel_b(q_i2b, sc_body_rate); + CalcAllPosVel_b(quaternion_i2b, sc_body_rate); return; } -void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate) { - libra::Vector<3> pos_center_i, vel_center_i; - double r_buf1_i[3], v_buf1_i[3], r_buf1_b[3], v_buf1_b[3]; - double r_buf2_i[3], v_buf2_i[3], r_buf2_b[3], v_buf2_b[3]; +void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate) { + libra::Vector<3> pos_centeposition_i, vel_centeposition_i; + double r_buf1_i[3], velocity_buf1_i[3], r_buf1_b[3], velocity_buf1_b[3]; + double r_buf2_i[3], velocity_buf2_i[3], r_buf2_b[3], velocity_buf2_b[3]; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { - pos_center_i = global_celestial_information_->GetPositionFromCenter_i_m(i); - vel_center_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); + pos_centeposition_i = global_celestial_information_->GetPositionFromCenter_i_m(i); + vel_centeposition_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); for (int j = 0; j < 3; j++) { - r_buf1_i[j] = pos_center_i[j]; + r_buf1_i[j] = pos_centeposition_i[j]; r_buf2_i[j] = celestial_body_position_from_spacecraft_i_m_[i * 3 + j]; - v_buf1_i[j] = vel_center_i[j]; - v_buf2_i[j] = celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j]; + velocity_buf1_i[j] = vel_centeposition_i[j]; + velocity_buf2_i[j] = celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j]; } - ConvertInertialToBody(r_buf1_i, r_buf1_b, q_i2b); - ConvertInertialToBody(r_buf2_i, r_buf2_b, q_i2b); - ConvertVelocityInertialToBody(r_buf1_i, v_buf1_i, v_buf1_b, q_i2b, sc_body_rate); - ConvertVelocityInertialToBody(r_buf2_i, v_buf2_i, v_buf2_b, q_i2b, sc_body_rate); + ConvertInertialToBody(r_buf1_i, r_buf1_b, quaternion_i2b); + ConvertInertialToBody(r_buf2_i, r_buf2_b, quaternion_i2b); + ConvertVelocityInertialToBody(r_buf1_i, velocity_buf1_i, velocity_buf1_b, quaternion_i2b, sc_body_rate); + ConvertVelocityInertialToBody(r_buf2_i, velocity_buf2_i, velocity_buf2_b, quaternion_i2b, sc_body_rate); for (int j = 0; j < 3; j++) { celestial_body_position_from_center_b_m_[i * 3 + j] = r_buf1_b[j]; celestial_body_position_from_spacecraft_b_m_[i * 3 + j] = r_buf2_b[j]; - celestial_body_velocity_from_center_b_m_s_[i * 3 + j] = v_buf1_b[j]; - celestial_body_velocity_from_spacecraft_b_m_s_[i * 3 + j] = v_buf2_b[j]; + celestial_body_velocity_from_center_b_m_s_[i * 3 + j] = velocity_buf1_b[j]; + celestial_body_velocity_from_spacecraft_b_m_s_[i * 3 + j] = velocity_buf2_b[j]; } } } -void LocalCelestialInformation::ConvertInertialToBody(const double* src_i, double* dst_b, libra::Quaternion q_i2b) { +void LocalCelestialInformation::ConvertInertialToBody(const double* input_i, double* output_b, libra::Quaternion quaternion_i2b) { libra::Vector<3> temp_i; for (int i = 0; i < 3; i++) { - temp_i[i] = src_i[i]; + temp_i[i] = input_i[i]; } - libra::Vector<3> temp_b = q_i2b.frame_conv(temp_i); + libra::Vector<3> temp_b = quaternion_i2b.frame_conv(temp_i); for (int i = 0; i < 3; i++) { - dst_b[i] = temp_b[i]; + output_b[i] = temp_b[i]; } } -void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* r_i, const double* v_i, double* v_b, libra::Quaternion q_i2b, - const libra::Vector<3> bodyrate_b) { +void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* position_i, const double* velocity_i, double* velocity_b, + libra::Quaternion quaternion_i2b, const libra::Vector<3> angular_velocity_b) { // copy input vector libra::Vector<3> vi; for (int i = 0; i < 3; i++) { - vi[i] = v_i[i]; + vi[i] = velocity_i[i]; } libra::Vector<3> ri; for (int i = 0; i < 3; i++) { - ri[i] = r_i[i]; + ri[i] = position_i[i]; } // convert body rate vector into that in inertial coordinate Vector<3> wb; for (int i = 0; i < 3; i++) { - wb[i] = bodyrate_b[i]; + wb[i] = angular_velocity_b[i]; } // compute cross term wxr - libra::Vector<3> wxr_i = outer_product(wb, ri); + libra::Vector<3> wxposition_i = outer_product(wb, ri); // compute dr/dt + wxr for (int i = 0; i < 3; i++) { - vi[i] = vi[i] - wxr_i[i]; + vi[i] = vi[i] - wxposition_i[i]; } // convert vector in inertial coordinate into that in body coordinate - libra::Vector<3> temp_b = q_i2b.frame_conv(vi); + libra::Vector<3> temp_b = quaternion_i2b.frame_conv(vi); for (int i = 0; i < 3; i++) { - v_b[i] = temp_b[i]; + velocity_b[i] = temp_b[i]; } } diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index a0e3a36de..88ca55bb1 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -29,20 +29,20 @@ class LocalCelestialInformation : public ILoggable { /** * @fn UpdateAllObjectsInfo * @brief Update the all selected celestial object local information - * @param [in] sc_pos_from_center_i: Spacecraft position from the center body in the inertial frame [m] - * @param [in] sc_vel_from_center_i: Spacecraft velocity from the center body in the inertial frame [m/s] - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] sc_pos_from_centeposition_i: Spacecraft position from the center body in the inertial frame [m] + * @param [in] sc_vel_from_centeposition_i: Spacecraft velocity from the center body in the inertial frame [m/s] + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_center_i, const libra::Vector<3> sc_vel_from_center_i, libra::Quaternion q_i2b, - const libra::Vector<3> sc_body_rate); + void UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_centeposition_i, const libra::Vector<3> sc_vel_from_centeposition_i, + libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate); /** * @fn CalcAllPosVel_b * @brief Frame conversion to the body frame for all selected celestial bodies - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void CalcAllPosVel_b(libra::Quaternion q_i2b, const libra::Vector<3> sc_body_rate); + void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate); /** * @fn GetPosFromSC_i @@ -99,23 +99,23 @@ class LocalCelestialInformation : public ILoggable { /** * @fn ConvertInertialToBody * @brief Convert position vector in the inertial frame to the body fixed frame - * @param [in] src_i: Source vector in the inertial frame - * @param [out] dst_b: Output vector in the body fixed frame - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] input_i: Source vector in the inertial frame + * @param [out] output_b: Output vector in the body fixed frame + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - void ConvertInertialToBody(const double* src_i, double* dst_b, const libra::Quaternion q_i2b); + void ConvertInertialToBody(const double* input_i, double* output_b, const libra::Quaternion quaternion_i2b); /** * @fn ConvertVelocityInertialToBody * @brief Convert velocity vector in the inertial frame to the body fixed frame - * @param [in] r_i: Position vector in the inertial frame - * @param [in] v_i: Velocity vector in the inertial frame - * @param [out] v_b: Output Velocity vector in the body fixed frame - * @param [in] q_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] + * @param [in] position_i: Position vector in the inertial frame + * @param [in] velocity_i: Velocity vector in the inertial frame + * @param [out] velocity_b: Output Velocity vector in the body fixed frame + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] angular_velocity_b: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void ConvertVelocityInertialToBody(const double* r_i, const double* v_i, double* v_b, const libra::Quaternion q_i2b, - const libra::Vector<3> bodyrate_b); + void ConvertVelocityInertialToBody(const double* position_i, const double* velocity_i, double* velocity_b, const libra::Quaternion quaternion_i2b, + const libra::Vector<3> angular_velocity_b); }; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_CELESTIAL_INFORMATION_HPP_ From d0b025dd99df35aa40526ae8e39e3c791372787c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:26:33 +0100 Subject: [PATCH 0538/1086] Fic function argument name --- .../local/local_celestial_information.cpp | 19 ++++++++++--------- .../local/local_celestial_information.hpp | 14 +++++++------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index dc0bf2cee..b104c67c0 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -42,25 +42,26 @@ LocalCelestialInformation::~LocalCelestialInformation() { delete[] celestial_body_velocity_from_spacecraft_b_m_s_; } -void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_centeposition_i, - const libra::Vector<3> sc_vel_from_centeposition_i, const libra::Quaternion quaternion_i2b, - const libra::Vector<3> sc_body_rate) { +void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, + const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, + const libra::Quaternion quaternion_i2b, + const libra::Vector<3> spacecraft_angular_velocity_rad_s) { Vector<3> pos_centeposition_i, vel_centeposition_i; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { pos_centeposition_i = global_celestial_information_->GetPositionFromCenter_i_m(i); vel_centeposition_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); // Change origin of frame for (int j = 0; j < 3; j++) { - celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_centeposition_i[j] - sc_pos_from_centeposition_i[j]; - celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_centeposition_i[j] - sc_vel_from_centeposition_i[j]; + celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_centeposition_i[j] - spacecraft_position_from_center_i_m[j]; + celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_centeposition_i[j] - spacecraft_velocity_from_center_i_m_s[j]; } } - CalcAllPosVel_b(quaternion_i2b, sc_body_rate); + CalcAllPosVel_b(quaternion_i2b, spacecraft_angular_velocity_rad_s); return; } -void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate) { +void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s) { libra::Vector<3> pos_centeposition_i, vel_centeposition_i; double r_buf1_i[3], velocity_buf1_i[3], r_buf1_b[3], velocity_buf1_b[3]; double r_buf2_i[3], velocity_buf2_i[3], r_buf2_b[3], velocity_buf2_b[3]; @@ -75,8 +76,8 @@ void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion quaterni } ConvertInertialToBody(r_buf1_i, r_buf1_b, quaternion_i2b); ConvertInertialToBody(r_buf2_i, r_buf2_b, quaternion_i2b); - ConvertVelocityInertialToBody(r_buf1_i, velocity_buf1_i, velocity_buf1_b, quaternion_i2b, sc_body_rate); - ConvertVelocityInertialToBody(r_buf2_i, velocity_buf2_i, velocity_buf2_b, quaternion_i2b, sc_body_rate); + ConvertVelocityInertialToBody(r_buf1_i, velocity_buf1_i, velocity_buf1_b, quaternion_i2b, spacecraft_angular_velocity_rad_s); + ConvertVelocityInertialToBody(r_buf2_i, velocity_buf2_i, velocity_buf2_b, quaternion_i2b, spacecraft_angular_velocity_rad_s); for (int j = 0; j < 3; j++) { celestial_body_position_from_center_b_m_[i * 3 + j] = r_buf1_b[j]; diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 88ca55bb1..0da9cab56 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -29,20 +29,20 @@ class LocalCelestialInformation : public ILoggable { /** * @fn UpdateAllObjectsInfo * @brief Update the all selected celestial object local information - * @param [in] sc_pos_from_centeposition_i: Spacecraft position from the center body in the inertial frame [m] - * @param [in] sc_vel_from_centeposition_i: Spacecraft velocity from the center body in the inertial frame [m/s] + * @param [in] spacecraft_position_from_center_i_m: Spacecraft position from the center body in the inertial frame [m] + * @param [in] spacecraft_velocity_from_center_i_m_s: Spacecraft velocity from the center body in the inertial frame [m/s] * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] + * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void UpdateAllObjectsInfo(const libra::Vector<3> sc_pos_from_centeposition_i, const libra::Vector<3> sc_vel_from_centeposition_i, - libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate); + void UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, + libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** * @fn CalcAllPosVel_b * @brief Frame conversion to the body frame for all selected celestial bodies * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - * @param [in] sc_body_rate: Spacecraft angular velocity with respect to the inertial frame [rad/s] + * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> sc_body_rate); + void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** * @fn GetPosFromSC_i From 4a08a97a9808c08f387d5a623ea287ce7f48126c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:28:45 +0100 Subject: [PATCH 0539/1086] Fic function argument name --- .../local/local_celestial_information.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index b104c67c0..67cbebc13 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -46,14 +46,14 @@ void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> spac const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s) { - Vector<3> pos_centeposition_i, vel_centeposition_i; + Vector<3> celestial_body_position_i_m, celestial_body_velocity_i_m_s; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { - pos_centeposition_i = global_celestial_information_->GetPositionFromCenter_i_m(i); - vel_centeposition_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); + celestial_body_position_i_m = global_celestial_information_->GetPositionFromCenter_i_m(i); + celestial_body_velocity_i_m_s = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); // Change origin of frame for (int j = 0; j < 3; j++) { - celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = pos_centeposition_i[j] - spacecraft_position_from_center_i_m[j]; - celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = vel_centeposition_i[j] - spacecraft_velocity_from_center_i_m_s[j]; + celestial_body_position_from_spacecraft_i_m_[i * 3 + j] = celestial_body_position_i_m[j] - spacecraft_position_from_center_i_m[j]; + celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j] = celestial_body_velocity_i_m_s[j] - spacecraft_velocity_from_center_i_m_s[j]; } } CalcAllPosVel_b(quaternion_i2b, spacecraft_angular_velocity_rad_s); @@ -62,16 +62,16 @@ void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> spac } void LocalCelestialInformation::CalcAllPosVel_b(const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s) { - libra::Vector<3> pos_centeposition_i, vel_centeposition_i; + libra::Vector<3> celestial_body_position_i_m, celestial_body_velocity_i_m_s; double r_buf1_i[3], velocity_buf1_i[3], r_buf1_b[3], velocity_buf1_b[3]; double r_buf2_i[3], velocity_buf2_i[3], r_buf2_b[3], velocity_buf2_b[3]; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { - pos_centeposition_i = global_celestial_information_->GetPositionFromCenter_i_m(i); - vel_centeposition_i = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); + celestial_body_position_i_m = global_celestial_information_->GetPositionFromCenter_i_m(i); + celestial_body_velocity_i_m_s = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); for (int j = 0; j < 3; j++) { - r_buf1_i[j] = pos_centeposition_i[j]; + r_buf1_i[j] = celestial_body_position_i_m[j]; r_buf2_i[j] = celestial_body_position_from_spacecraft_i_m_[i * 3 + j]; - velocity_buf1_i[j] = vel_centeposition_i[j]; + velocity_buf1_i[j] = celestial_body_velocity_i_m_s[j]; velocity_buf2_i[j] = celestial_body_velocity_from_spacecraft_i_m_s_[i * 3 + j]; } ConvertInertialToBody(r_buf1_i, r_buf1_b, quaternion_i2b); From 17eb8d70853d55d45f2ca364181bb7acfaf965ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:29:58 +0100 Subject: [PATCH 0540/1086] Move public function to private function --- .../local/local_celestial_information.hpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 0da9cab56..9c442d03e 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -36,13 +36,6 @@ class LocalCelestialInformation : public ILoggable { */ void UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); - /** - * @fn CalcAllPosVel_b - * @brief Frame conversion to the body frame for all selected celestial bodies - * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame - * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] - */ - void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** * @fn GetPosFromSC_i @@ -96,6 +89,14 @@ class LocalCelestialInformation : public ILoggable { double* celestial_body_velocity_from_center_b_m_s_; //!< Celestial body velocity from the center body in the spacecraft body fixed frame [m/s] double* celestial_body_velocity_from_spacecraft_b_m_s_; //!< Celestial body velocity from the spacecraft in the spacecraft body fixed frame [m/s] + /** + * @fn CalcAllPosVel_b + * @brief Frame conversion to the body frame for all selected celestial bodies + * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame + * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] + */ + void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); + /** * @fn ConvertInertialToBody * @brief Convert position vector in the inertial frame to the body fixed frame From d8ad5136d77c48465454d8c1fa993aaa862915c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:32:34 +0100 Subject: [PATCH 0541/1086] Add libra:: --- src/environment/local/local_celestial_information.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 67cbebc13..233a0cb43 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -46,7 +46,7 @@ void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> spac const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s) { - Vector<3> celestial_body_position_i_m, celestial_body_velocity_i_m_s; + libra::Vector<3> celestial_body_position_i_m, celestial_body_velocity_i_m_s; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { celestial_body_position_i_m = global_celestial_information_->GetPositionFromCenter_i_m(i); celestial_body_velocity_i_m_s = global_celestial_information_->GetVelocityFromCenter_i_m_s(i); @@ -112,7 +112,7 @@ void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* posi } // convert body rate vector into that in inertial coordinate - Vector<3> wb; + libra::Vector<3> wb; for (int i = 0; i < 3; i++) { wb[i] = angular_velocity_b[i]; } @@ -142,7 +142,7 @@ libra::Vector<3> LocalCelestialInformation::GetPosFromSC_i(const char* body_name Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_i() const { std::string body_name = global_celestial_information_->GetCenterBodyName(); - Vector<3> position = GetPosFromSC_i(body_name.c_str()); + libra::Vector<3> position = GetPosFromSC_i(body_name.c_str()); return position; } From 713d3ced4752f68822c3fea2939ba63ae6daf3ee Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:34:13 +0100 Subject: [PATCH 0542/1086] Add const --- src/environment/local/local_celestial_information.cpp | 2 +- src/environment/local/local_celestial_information.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 233a0cb43..2badad988 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -100,7 +100,7 @@ void LocalCelestialInformation::ConvertInertialToBody(const double* input_i, dou } void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* position_i, const double* velocity_i, double* velocity_b, - libra::Quaternion quaternion_i2b, const libra::Vector<3> angular_velocity_b) { + const libra::Quaternion quaternion_i2b, const libra::Vector<3> angular_velocity_b) { // copy input vector libra::Vector<3> vi; for (int i = 0; i < 3; i++) { diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 9c442d03e..22788123a 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -35,7 +35,7 @@ class LocalCelestialInformation : public ILoggable { * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ void UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, - libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); + const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** * @fn GetPosFromSC_i @@ -95,7 +95,7 @@ class LocalCelestialInformation : public ILoggable { * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void CalcAllPosVel_b(libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); + void CalcAllPosVel_b(const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** * @fn ConvertInertialToBody From 39ea53a470669db194d65519837d1d8b4590f47f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:41:42 +0100 Subject: [PATCH 0543/1086] Fix public function name --- src/components/real/aocs/star_sensor.cpp | 6 ++--- src/components/real/aocs/sun_sensor.cpp | 2 +- src/components/real/mission/telescope.cpp | 18 +++++++-------- .../real/power/solar_array_panel.cpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- .../solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/third_body_gravity.cpp | 4 ++-- src/dynamics/attitude/controlled_attitude.cpp | 4 ++-- src/dynamics/dynamics.cpp | 6 ++--- .../local/local_celestial_information.cpp | 20 ++++++++-------- .../local/local_celestial_information.hpp | 23 ++++++++++--------- src/environment/local/local_environment.cpp | 2 +- .../solar_radiation_pressure_environment.cpp | 12 +++++----- 14 files changed, 53 insertions(+), 52 deletions(-) diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index c0364477c..f9e801510 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -123,9 +123,9 @@ void STT::update(const LocalCelestialInformation* local_celes_info, const Attitu void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { int judgement = 0; - judgement = SunJudgement(local_celes_info->GetPosFromSC_b("SUN")); - judgement += EarthJudgement(local_celes_info->GetPosFromSC_b("EARTH")); - judgement += MoonJudgement(local_celes_info->GetPosFromSC_b("MOON")); + judgement = SunJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("SUN")); + judgement += EarthJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("EARTH")); + judgement += MoonJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("MOON")); judgement += CaptureRateJudgement(attinfo->GetOmega_b()); if (judgement > 0) error_flag_ = true; diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 67a251b61..276ddab37 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -56,7 +56,7 @@ void SunSensor::MainRoutine(int count) { } void SunSensor::measure() { - Vector<3> sun_pos_b = local_celes_info_->GetPosFromSC_b("SUN"); + Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); Vector<3> sun_dir_b = normalize(sun_pos_b); sun_c_ = q_b2c_.frame_conv(sun_dir_b); // Frame conversion from body to component diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index c268ebffa..87de9b002 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -59,20 +59,20 @@ Telescope::~Telescope() {} void Telescope::MainRoutine(int count) { UNUSED(count); // Check forbidden angle - is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("SUN"), sun_forbidden_angle_); - is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("EARTH"), earth_forbidden_angle_); - is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPosFromSC_b("MOON"), moon_forbidden_angle_); + is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_); + is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_); + is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_); // Position calculation of celestial bodies from CelesInfo - Observe(sun_pos_imgsensor, local_celes_info_->GetPosFromSC_b("SUN")); - Observe(earth_pos_imgsensor, local_celes_info_->GetPosFromSC_b("EARTH")); - Observe(moon_pos_imgsensor, local_celes_info_->GetPosFromSC_b("MOON")); + Observe(sun_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("SUN")); + Observe(earth_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH")); + Observe(moon_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("MOON")); // Position calculation of stars from Hipparcos Catalogue // No update when Hipparocos Catalogue was not readed if (hipp_->IsCalcEnabled) ObserveStars(); // Debug ****************************************************************** - // sun_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("SUN")); - // earth_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("EARTH")); - // moon_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPosFromSC_b("MOON")); + // sun_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); + // earth_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); + // moon_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); // angle_sun = angle(sight_, sun_pos_c) * 180/libra::pi; // angle_earth = angle(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = angle(sight_, moon_pos_c) * 180 / libra::pi; //****************************************************************************** diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index ec61cc424..d21b2d556 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -104,7 +104,7 @@ void SAP::MainRoutine(int time_count) { cell_area_ * number_of_parallel_ * number_of_series_ * inner_product(normal_vector_, normalized_sun_direction_body); } else { const auto power_density = srp_->CalcPowerDensity(); - libra::Vector<3> sun_pos_b = local_celes_info_->GetPosFromSC_b("SUN"); + libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = libra::normalize(sun_pos_b); power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * inner_product(normal_vector_, sun_dir_b); diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 0b2132df7..72cb53503 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -78,7 +78,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif - Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInfo().GetEarthRotation().GetDcmJ2000ToXcxf(); + Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index e2a3055d1..4226b5024 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -18,7 +18,7 @@ GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculatio void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor - CalcTorque_b_Nm(local_environment.GetCelesInfo().GetCenterBodyPosFromSC_b(), dynamics.GetAttitude().GetInertiaTensor()); + CalcTorque_b_Nm(local_environment.GetCelesInfo().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); } libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 1e88e789d..081197792 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -15,7 +15,7 @@ SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vec void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); - libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelesInfo().GetPosFromSC_b("SUN"); + libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelesInfo().GetPositionFromSpacecraft_b_m("SUN"); CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSrp().CalcTruePressure()); } diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index b32e64181..937d2e234 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -17,9 +17,9 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> sc_position_i_m = dynamics.GetOrbit().GetSatPosition_i(); for (auto third_body : third_body_list_) { - libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelesInfo().GetPosFromSC_i(third_body.c_str()); + libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelesInfo(). GetPositionFromSpacecraft_i_m(third_body.c_str()); libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; - double gravity_constant = local_environment.GetCelesInfo().GetGlobalInfo().GetGravityConstant_m3_s2(third_body.c_str()); + double gravity_constant = local_environment.GetCelesInfo().GetGlobalInformation().GetGravityConstant_m3_s2(third_body.c_str()); third_body_acceleration_i_m_s2_ = CalcAcceleration_i_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 4aa314c7f..2f86e16c3 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -81,9 +81,9 @@ void ControlledAttitude::Propagate(const double endtime_s) { Vector<3> ControlledAttitude::CalcTargetDirection(AttCtrlMode mode) { Vector<3> direction; if (mode == SUN_POINTING) { - direction = local_celes_info_->GetPosFromSC_i("SUN"); + direction = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); } else if (mode == EARTH_CENTER_POINTING) { - direction = local_celes_info_->GetPosFromSC_i("EARTH"); + direction = local_celes_info_->GetPositionFromSpacecraft_i_m("EARTH"); } else if (mode == VELOCITY_DIRECTION_POINTING) { direction = orbit_->GetSatVelocity_i(); } else if (mode == ORBIT_NORMAL_POINTING) { diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index f0df0b540..c4d94f4ae 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -25,8 +25,8 @@ void Dynamics::Initialize(SimulationConfig* sim_config, const SimTime* sim_time, structure_ = structure; // Initialize - orbit_ = InitOrbit(&(local_celes_info->GetGlobalInfo()), sim_config->sat_file_[sat_id], sim_time->GetOrbitRkStepTime_s(), - sim_time->GetCurrentTime_jd(), local_celes_info->GetGlobalInfo().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", rel_info); + orbit_ = InitOrbit(&(local_celes_info->GetGlobalInformation()), sim_config->sat_file_[sat_id], sim_time->GetOrbitRkStepTime_s(), + sim_time->GetCurrentTime_jd(), local_celes_info->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", rel_info); attitude_ = InitAttitude(sim_config->sat_file_[sat_id], orbit_, local_celes_info, sim_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor(), sat_id); temperature_ = InitTemperature(sim_config->sat_file_[sat_id], sim_time->GetThermalRkStepTime_s()); @@ -52,7 +52,7 @@ void Dynamics::Update(const SimTime* sim_time, const LocalCelestialInformation* std::string sun_str = "SUN"; char* c_sun = new char[sun_str.size() + 1]; std::char_traits::copy(c_sun, sun_str.c_str(), sun_str.size() + 1); // string -> char* - temperature_->Propagate(local_celes_info->GetPosFromSC_b(c_sun), sim_time->GetElapsedTime_s()); + temperature_->Propagate(local_celes_info->GetPositionFromSpacecraft_b_m(c_sun), sim_time->GetElapsedTime_s()); delete[] c_sun; } } diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 2badad988..0565b0d10 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -42,10 +42,10 @@ LocalCelestialInformation::~LocalCelestialInformation() { delete[] celestial_body_velocity_from_spacecraft_b_m_s_; } -void LocalCelestialInformation::UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, - const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, - const libra::Quaternion quaternion_i2b, - const libra::Vector<3> spacecraft_angular_velocity_rad_s) { +void LocalCelestialInformation::UpdateAllObjectsInformation(const libra::Vector<3> spacecraft_position_from_center_i_m, + const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, + const libra::Quaternion quaternion_i2b, + const libra::Vector<3> spacecraft_angular_velocity_rad_s) { libra::Vector<3> celestial_body_position_i_m, celestial_body_velocity_i_m_s; for (int i = 0; i < global_celestial_information_->GetNumberOfSelectedBodies(); i++) { celestial_body_position_i_m = global_celestial_information_->GetPositionFromCenter_i_m(i); @@ -130,7 +130,7 @@ void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* posi } } -libra::Vector<3> LocalCelestialInformation::GetPosFromSC_i(const char* body_name) const { +libra::Vector<3> LocalCelestialInformation::GetPositionFromSpacecraft_i_m(const char* body_name) const { libra::Vector<3> position; int index = 0; index = global_celestial_information_->CalcBodyIdFromName(body_name); @@ -140,13 +140,13 @@ libra::Vector<3> LocalCelestialInformation::GetPosFromSC_i(const char* body_name return position; } -Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_i() const { +Vector<3> LocalCelestialInformation::GetCenterBodyPositionFromSpacecraft_i_m() const { std::string body_name = global_celestial_information_->GetCenterBodyName(); - libra::Vector<3> position = GetPosFromSC_i(body_name.c_str()); + libra::Vector<3> position = GetPositionFromSpacecraft_i_m(body_name.c_str()); return position; } -libra::Vector<3> LocalCelestialInformation::GetPosFromSC_b(const char* body_name) const { +libra::Vector<3> LocalCelestialInformation::GetPositionFromSpacecraft_b_m(const char* body_name) const { libra::Vector<3> position; int index = 0; index = global_celestial_information_->CalcBodyIdFromName(body_name); @@ -156,9 +156,9 @@ libra::Vector<3> LocalCelestialInformation::GetPosFromSC_b(const char* body_name return position; } -libra::Vector<3> LocalCelestialInformation::GetCenterBodyPosFromSC_b(void) const { +libra::Vector<3> LocalCelestialInformation::GetCenterBodyPositionFromSpacecraft_b_m(void) const { std::string body_name = global_celestial_information_->GetCenterBodyName(); - libra::Vector<3> position = GetPosFromSC_b(body_name.c_str()); + libra::Vector<3> position = GetPositionFromSpacecraft_b_m(body_name.c_str()); return position; } diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 22788123a..30f67942f 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -34,38 +34,39 @@ class LocalCelestialInformation : public ILoggable { * @param [in] quaternion_i2b: Spacecraft attitude quaternion from the inertial frame to the body fixed frame * @param [in] spacecraft_angular_velocity_rad_s: Spacecraft angular velocity with respect to the inertial frame [rad/s] */ - void UpdateAllObjectsInfo(const libra::Vector<3> spacecraft_position_from_center_i_m, const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, - const libra::Quaternion quaternion_i2b, const libra::Vector<3> spacecraft_angular_velocity_rad_s); + void UpdateAllObjectsInformation(const libra::Vector<3> spacecraft_position_from_center_i_m, + const libra::Vector<3> spacecraft_velocity_from_center_i_m_s, const libra::Quaternion quaternion_i2b, + const libra::Vector<3> spacecraft_angular_velocity_rad_s); /** - * @fn GetPosFromSC_i + * @fn GetPositionFromSpacecraft_i_m * @brief Return position of a selected body (Origin: Spacecraft, Frame: Inertial frame) * @param [in] body_name Celestial body name */ - libra::Vector<3> GetPosFromSC_i(const char* body_name) const; + libra::Vector<3> GetPositionFromSpacecraft_i_m(const char* body_name) const; /** - * @fn GetCenterBodyPosFromSC_i + * @fn GetCenterBodyPositionFromSpacecraft_i_m * @brief Return position of the center body (Origin: Spacecraft, Frame: Inertial frame) */ - libra::Vector<3> GetCenterBodyPosFromSC_i(void) const; + libra::Vector<3> GetCenterBodyPositionFromSpacecraft_i_m(void) const; /** - * @fn GetPosFromSC_b + * @fn GetPositionFromSpacecraft_b_m * @brief Return position of a selected body (Origin: Spacecraft, Frame: Body fixed frame) * @param [in] body_name Celestial body name */ - libra::Vector<3> GetPosFromSC_b(const char* body_name) const; + libra::Vector<3> GetPositionFromSpacecraft_b_m(const char* body_name) const; /** - * @fn GetCenterBodyPosFromSC_b + * @fn GetCenterBodyPositionFromSpacecraft_b_m * @brief Return position of the center body (Origin: Spacecraft, Frame: Body fixed frame) */ - libra::Vector<3> GetCenterBodyPosFromSC_b(void) const; + libra::Vector<3> GetCenterBodyPositionFromSpacecraft_b_m(void) const; /** * @fn GetGlobalInfo * @brief Return global celestial information */ - inline const CelestialInformation& GetGlobalInfo() const { return *global_celestial_information_; } + inline const CelestialInformation& GetGlobalInformation() const { return *global_celestial_information_; } // Override ILoggable /** diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index c26a69235..ece79c2ea 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -49,7 +49,7 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { - celes_info_->UpdateAllObjectsInfo(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); + celes_info_->UpdateAllObjectsInformation(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); mag_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), attitude.GetQuaternion_i2b()); } diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 6c2c500a6..25df58e19 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -18,8 +18,8 @@ using namespace std; SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : local_celes_info_(local_celes_info) { solar_constant_ = 1366.0; // [W/m2] pressure_ = solar_constant_ / environment::speed_of_light_m_s; // [N/m2] - shadow_source_name_ = local_celes_info_->GetGlobalInfo().GetCenterBodyName(); - sun_radius_m_ = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName_m("SUN"); + shadow_source_name_ = local_celes_info_->GetGlobalInformation().GetCenterBodyName(); + sun_radius_m_ = local_celes_info_->GetGlobalInformation().GetMeanRadiusFromName_m("SUN"); } void SRPEnvironment::UpdateAllStates() { @@ -30,7 +30,7 @@ void SRPEnvironment::UpdateAllStates() { } void SRPEnvironment::UpdatePressure() { - const Vector<3> r_sc2sun_eci = local_celes_info_->GetPosFromSC_i("SUN"); + const Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); const double distance_sat_to_sun = norm(r_sc2sun_eci); pressure_ = solar_constant_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } @@ -69,10 +69,10 @@ void SRPEnvironment::CalcShadowCoefficient(string shadow_source_name) { return; } - const Vector<3> r_sc2sun_eci = local_celes_info_->GetPosFromSC_i("SUN"); - const Vector<3> r_sc2source_eci = local_celes_info_->GetPosFromSC_i(shadow_source_name.c_str()); + const Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); + const Vector<3> r_sc2source_eci = local_celes_info_->GetPositionFromSpacecraft_i_m(shadow_source_name.c_str()); - const double shadow_source_radius_m = local_celes_info_->GetGlobalInfo().GetMeanRadiusFromName_m(shadow_source_name.c_str()); + const double shadow_source_radius_m = local_celes_info_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); const double distance_sat_to_sun = norm(r_sc2sun_eci); const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun From 79152a3c15137651428116fc3f4c02df21b34788 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:43:37 +0100 Subject: [PATCH 0544/1086] Fix include files --- src/environment/local/local_environment.cpp | 7 +++---- src/environment/local/local_environment.hpp | 8 ++------ 2 files changed, 5 insertions(+), 10 deletions(-) diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index ece79c2ea..84afb8140 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -4,11 +4,10 @@ */ #include "local_environment.hpp" -#include -#include -#include - +#include "dynamics/attitude/attitude.hpp" +#include "dynamics/orbit/orbit.hpp" #include "initialize_local_environment.hpp" +#include "library/initialize/initialize_file_access.hpp" LocalEnvironment::LocalEnvironment(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { Initialize(sim_config, glo_env, sat_id); diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 56afdfdf2..46c78b7b7 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -6,18 +6,14 @@ #ifndef S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ -#include -#include - #include "atmosphere.hpp" +#include "dynamics/dynamics.hpp" +#include "environment/global/global_environment.hpp" #include "geomagnetic_field.hpp" #include "local_celestial_information.hpp" #include "simulation/simulation_configuration.hpp" #include "solar_radiation_pressure_environment.hpp" -class Logger; -class SimTime; - /** * @class LocalEnvironment * @brief Class to manage local environments From a1fdca19c308e45bb78e2640e3203762965a58bd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:46:31 +0100 Subject: [PATCH 0545/1086] Fix private member names --- src/environment/local/local_environment.cpp | 31 +++++++++++---------- src/environment/local/local_environment.hpp | 14 +++++----- 2 files changed, 23 insertions(+), 22 deletions(-) diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 84afb8140..9341f648d 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -14,10 +14,10 @@ LocalEnvironment::LocalEnvironment(SimulationConfig* sim_config, const GlobalEnv } LocalEnvironment::~LocalEnvironment() { - delete mag_; - delete srp_; + delete geomagnetic_field_; + delete solar_radiation_pressure_environment_; delete atmosphere_; - delete celes_info_; + delete celestial_information_; } void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { @@ -27,19 +27,19 @@ void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvi // Save ini file sim_config->main_logger_->CopyFileToLogDir(ini_fname); // Initialize - mag_ = new GeomagneticField(InitGeomagneticField(ini_fname)); + geomagnetic_field_ = new GeomagneticField(InitGeomagneticField(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); - celes_info_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); - srp_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celes_info_)); + celestial_information_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); + solar_radiation_pressure_environment_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celestial_information_)); // Force to disable when the center body is not the Earth if (glo_env->GetCelestialInformation().GetCenterBodyName() != "EARTH") { - mag_->IsCalcEnabled = false; + geomagnetic_field_->IsCalcEnabled = false; atmosphere_->IsCalcEnabled = false; } // Log setting for Local celestial information IniAccess conf = IniAccess(ini_fname); - celes_info_->IsLogEnabled = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); + celestial_information_->IsLogEnabled = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); } void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) { @@ -48,21 +48,22 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) // Update local environments that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { - celes_info_->UpdateAllObjectsInformation(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); - mag_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), - attitude.GetQuaternion_i2b()); + celestial_information_->UpdateAllObjectsInformation(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), + attitude.GetOmega_b()); + geomagnetic_field_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), + attitude.GetQuaternion_i2b()); } // Update local environments that depend only on the position if (sim_time->GetOrbitPropagateFlag()) { - srp_->UpdateAllStates(); + solar_radiation_pressure_environment_->UpdateAllStates(); atmosphere_->CalcAirDensity_kg_m3(sim_time->GetCurrentDecimalYear(), sim_time->GetEndTime_s(), orbit.GetGeodeticPosition()); } } void LocalEnvironment::LogSetup(Logger& logger) { - logger.AddLoggable(mag_); - logger.AddLoggable(srp_); + logger.AddLoggable(geomagnetic_field_); + logger.AddLoggable(solar_radiation_pressure_environment_); logger.AddLoggable(atmosphere_); - logger.AddLoggable(celes_info_); + logger.AddLoggable(celestial_information_); } diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 46c78b7b7..fad5f37c2 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -65,23 +65,23 @@ class LocalEnvironment { * @fn GetMag * @brief Return GeomagneticField class */ - inline const GeomagneticField& GetMag() const { return *mag_; } + inline const GeomagneticField& GetMag() const { return *geomagnetic_field_; } /** * @fn GetSrp * @brief Return SRPEnvironment class */ - inline const SRPEnvironment& GetSrp() const { return *srp_; } + inline const SRPEnvironment& GetSrp() const { return *solar_radiation_pressure_environment_; } /** * @fn GetCelesInfo * @brief Return LocalCelestialInformation class */ - inline const LocalCelestialInformation& GetCelesInfo() const { return *celes_info_; } + inline const LocalCelestialInformation& GetCelesInfo() const { return *celestial_information_; } private: - Atmosphere* atmosphere_; //!< Atmospheric density of the earth - GeomagneticField* mag_; //!< Magnetic field of the earth - SRPEnvironment* srp_; //!< Solar radiation pressure - LocalCelestialInformation* celes_info_; //!< Celestial information + Atmosphere* atmosphere_; //!< Atmospheric density of the earth + GeomagneticField* geomagnetic_field_; //!< Magnetic field of the earth + SRPEnvironment* solar_radiation_pressure_environment_; //!< Solar radiation pressure + LocalCelestialInformation* celestial_information_; //!< Celestial information }; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ From 1e412efa6ea6d728f9f8f47e2d2cc2e5e2d8a781 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:49:37 +0100 Subject: [PATCH 0546/1086] Fix function argument names --- src/environment/local/local_environment.cpp | 29 ++++++++++++--------- src/environment/local/local_environment.hpp | 20 +++++++------- 2 files changed, 26 insertions(+), 23 deletions(-) diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 9341f648d..e3463098a 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -9,8 +9,8 @@ #include "initialize_local_environment.hpp" #include "library/initialize/initialize_file_access.hpp" -LocalEnvironment::LocalEnvironment(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { - Initialize(sim_config, glo_env, sat_id); +LocalEnvironment::LocalEnvironment(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { + Initialize(simulation_configuration, global_environment, spacecraft_id); } LocalEnvironment::~LocalEnvironment() { @@ -20,19 +20,22 @@ LocalEnvironment::~LocalEnvironment() { delete celestial_information_; } -void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { +void LocalEnvironment::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { // Read file name - IniAccess iniAccess = IniAccess(sim_config->sat_file_[sat_id]); + IniAccess iniAccess = IniAccess(simulation_configuration->sat_file_[spacecraft_id]); std::string ini_fname = iniAccess.ReadString("SETTING_FILES", "local_environment_file"); + // Save ini file - sim_config->main_logger_->CopyFileToLogDir(ini_fname); + simulation_configuration->main_logger_->CopyFileToLogDir(ini_fname); + // Initialize geomagnetic_field_ = new GeomagneticField(InitGeomagneticField(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); - celestial_information_ = new LocalCelestialInformation(&(glo_env->GetCelestialInformation())); + celestial_information_ = new LocalCelestialInformation(&(global_environment->GetCelestialInformation())); solar_radiation_pressure_environment_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celestial_information_)); + // Force to disable when the center body is not the Earth - if (glo_env->GetCelestialInformation().GetCenterBodyName() != "EARTH") { + if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") { geomagnetic_field_->IsCalcEnabled = false; atmosphere_->IsCalcEnabled = false; } @@ -42,22 +45,22 @@ void LocalEnvironment::Initialize(SimulationConfig* sim_config, const GlobalEnvi celestial_information_->IsLogEnabled = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); } -void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* sim_time) { +void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* simulation_time) { auto& orbit = dynamics->GetOrbit(); auto& attitude = dynamics->GetAttitude(); // Update local environments that depend on the attitude (and the position) - if (sim_time->GetAttitudePropagateFlag()) { + if (simulation_time->GetAttitudePropagateFlag()) { celestial_information_->UpdateAllObjectsInformation(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); - geomagnetic_field_->CalcMagneticField(sim_time->GetCurrentDecimalYear(), sim_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), - attitude.GetQuaternion_i2b()); + geomagnetic_field_->CalcMagneticField(simulation_time->GetCurrentDecimalYear(), simulation_time->GetCurrentSiderealTime(), + orbit.GetGeodeticPosition(), attitude.GetQuaternion_i2b()); } // Update local environments that depend only on the position - if (sim_time->GetOrbitPropagateFlag()) { + if (simulation_time->GetOrbitPropagateFlag()) { solar_radiation_pressure_environment_->UpdateAllStates(); - atmosphere_->CalcAirDensity_kg_m3(sim_time->GetCurrentDecimalYear(), sim_time->GetEndTime_s(), orbit.GetGeodeticPosition()); + atmosphere_->CalcAirDensity_kg_m3(simulation_time->GetCurrentDecimalYear(), simulation_time->GetEndTime_s(), orbit.GetGeodeticPosition()); } } diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index fad5f37c2..e867c3966 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -23,11 +23,11 @@ class LocalEnvironment { /** * @fn LocalEnvironment * @brief Constructor - * @param [in] sim_config: Simulation configuration - * @param [in] glo_env: Global environment - * @param [in] sat_id: Satellite ID + * @param [in] simulation_configuration: Simulation configuration + * @param [in] global_environment: Global environment + * @param [in] spacecraft_id: Satellite ID */ - LocalEnvironment(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id); + LocalEnvironment(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn ~LocalEnvironment * @brief Destructor @@ -36,19 +36,19 @@ class LocalEnvironment { /** * @fn Initialize * @brief Initialize function - * @param [in] sim_config: Simulation configuration - * @param [in] glo_env: Global environment - * @param [in] sat_id: Satellite ID + * @param [in] simulation_configuration: Simulation configuration + * @param [in] global_environment: Global environment + * @param [in] spacecraft_id: Satellite ID */ - void Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id); + void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Update * @brief Update all states * @param [in] dynamics: Dynamics information of the satellite - * @param [in] sim_time: Simulation time + * @param [in] simulation_time: Simulation time */ - void Update(const Dynamics* dynamics, const SimTime* sim_time); + void Update(const Dynamics* dynamics, const SimTime* simulation_time); /** * @fn LogSetup From 85a3087dd69b4fc39c31826a93df4bbaecc2857d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:50:50 +0100 Subject: [PATCH 0547/1086] Add const --- src/environment/local/local_environment.cpp | 6 ++++-- src/environment/local/local_environment.hpp | 4 ++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index e3463098a..fd4d9ab8d 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -9,7 +9,8 @@ #include "initialize_local_environment.hpp" #include "library/initialize/initialize_file_access.hpp" -LocalEnvironment::LocalEnvironment(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { +LocalEnvironment::LocalEnvironment(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + const int spacecraft_id) { Initialize(simulation_configuration, global_environment, spacecraft_id); } @@ -20,7 +21,8 @@ LocalEnvironment::~LocalEnvironment() { delete celestial_information_; } -void LocalEnvironment::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { +void LocalEnvironment::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + const int spacecraft_id) { // Read file name IniAccess iniAccess = IniAccess(simulation_configuration->sat_file_[spacecraft_id]); std::string ini_fname = iniAccess.ReadString("SETTING_FILES", "local_environment_file"); diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index e867c3966..6ed3bfe41 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -27,7 +27,7 @@ class LocalEnvironment { * @param [in] global_environment: Global environment * @param [in] spacecraft_id: Satellite ID */ - LocalEnvironment(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + LocalEnvironment(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn ~LocalEnvironment * @brief Destructor @@ -40,7 +40,7 @@ class LocalEnvironment { * @param [in] global_environment: Global environment * @param [in] spacecraft_id: Satellite ID */ - void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Update From a0e93e3912ab7a560c5f44b137962ae1af681405 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:53:14 +0100 Subject: [PATCH 0548/1086] Fix public function name --- src/components/real/aocs/magnetometer.cpp | 4 ++-- src/components/real/aocs/magnetometer.hpp | 4 ++-- src/components/real/aocs/magnetorquer.cpp | 2 +- src/components/real/aocs/magnetorquer.hpp | 4 ++-- src/components/real/aocs/star_sensor.cpp | 2 +- src/disturbances/geopotential.cpp | 2 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- .../solar_radiation_pressure_disturbance.cpp | 4 ++-- src/disturbances/third_body_gravity.cpp | 4 ++-- src/environment/global/global_environment.hpp | 2 +- src/environment/local/geomagnetic_field.hpp | 8 ++++---- src/environment/local/local_environment.hpp | 12 ++++++------ .../sample_spacecraft/sample_components.cpp | 11 ++++++----- src/simulation/spacecraft/spacecraft.cpp | 6 +++--- 15 files changed, 35 insertions(+), 34 deletions(-) diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 24cdc11ab..2f7d378dc 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -17,8 +17,8 @@ MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = q_b2c_.frame_conv(magnet_->GetMagneticField_b_nT()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + mag_c_ = q_b2c_.frame_conv(magnet_->GetGeomagneticFieldneticField_b_nT()); // Convert frame + mag_c_ = Measure(mag_c_); // Add noises } std::string MagSensor::GetLogHeader() const { diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index eef494fd9..09ee06eb5 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -72,10 +72,10 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg virtual std::string GetLogValue() const; /** - * @fn GetMagC + * @fn GetGeomagneticFieldC * @brief Return observed magnetic field on the component frame */ - inline const libra::Vector& GetMagC(void) const { return mag_c_; } + inline const libra::Vector& GetGeomagneticFieldC(void) const { return mag_c_; } protected: libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index bbe15c1d1..182304afc 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -74,7 +74,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { // Frame conversion component to body mag_moment_b_ = q_c2b_.frame_conv(mag_moment_c_); // Calc magnetic torque [Nm] - torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetMagneticField_b_nT()); + torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetGeomagneticFieldneticField_b_nT()); // Update Random Walk ++n_rw_c_; diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index ef66997a4..d4ae0d1b4 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -93,10 +93,10 @@ class MagTorquer : public ComponentBase, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetMagMoment_b + * @fn GetGeomagneticFieldMoment_b * @brief Return output magnetic moment in the body fixed frame [Am2] */ - inline const libra::Vector& GetMagMoment_b(void) const { return mag_moment_b_; }; + inline const libra::Vector& GetGeomagneticFieldMoment_b(void) const { return mag_moment_b_; }; /** * @fn GetTorque_b * @brief Return output torque in the body fixed frame [Nm] diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index f9e801510..969526144 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -207,5 +207,5 @@ double STT::CalAngleVect_rad(const Vector<3>& vect1, const Vector<3>& vect2) { void STT::MainRoutine(int count) { UNUSED(count); - measure(&(local_env_->GetCelesInfo()), &(dynamics_->GetAttitude())); + measure(&(local_env_->GetCelestialInformation()), &(dynamics_->GetAttitude())); } diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 72cb53503..9243178be 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -78,7 +78,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif - Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelesInfo().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); + Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelestialInformation().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 4226b5024..479450d36 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -18,7 +18,7 @@ GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculatio void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor - CalcTorque_b_Nm(local_environment.GetCelesInfo().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); + CalcTorque_b_Nm(local_environment.GetCelestialInformation().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); } libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 632d06fa5..910597e94 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -26,7 +26,7 @@ Vector<3> MagDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) void MagDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - CalcTorque_b_Nm(local_environment.GetMag().GetMagneticField_b_nT()); + CalcTorque_b_Nm(local_environment.GetGeomagneticField().GetGeomagneticFieldneticField_b_nT()); } void MagDisturbance::CalcRMM() { diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 081197792..24a2e0bfa 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -15,8 +15,8 @@ SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vec void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); - libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelesInfo().GetPositionFromSpacecraft_b_m("SUN"); - CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSrp().CalcTruePressure()); + libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); + CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().CalcTruePressure()); } void SolarRadiation::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 937d2e234..aeaec6197 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -17,9 +17,9 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> sc_position_i_m = dynamics.GetOrbit().GetSatPosition_i(); for (auto third_body : third_body_list_) { - libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelesInfo(). GetPositionFromSpacecraft_i_m(third_body.c_str()); + libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelestialInformation().GetPositionFromSpacecraft_i_m(third_body.c_str()); libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; - double gravity_constant = local_environment.GetCelesInfo().GetGlobalInformation().GetGravityConstant_m3_s2(third_body.c_str()); + double gravity_constant = local_environment.GetCelestialInformation().GetGlobalInformation().GetGravityConstant_m3_s2(third_body.c_str()); third_body_acceleration_i_m_s2_ = CalcAcceleration_i_m_s2(third_body_pos_i_m, third_body_position_from_sc_i_m, gravity_constant); acceleration_i_m_s2_ += third_body_acceleration_i_m_s2_; diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index bc9b5939b..5e5cea05e 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -60,7 +60,7 @@ class GlobalEnvironment { */ inline const SimTime& GetSimulationTime() const { return *simulation_time_; } /** - * @fn GetCelesInfo + * @fn GetCelestialInformation * @brief Return CelestialInformation */ inline const CelestialInformation& GetCelestialInformation() const { return *celestial_information_; } diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 9e3a38402..049a614cd 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -47,15 +47,15 @@ class GeomagneticField : public ILoggable { const libra::Quaternion quaternion_i2b); /** - * @fn GetMagneticField_i_nT + * @fn GetGeomagneticFieldneticField_i_nT * @brief Return magnetic field vector in the inertial frame [nT] */ - inline libra::Vector<3> GetMagneticField_i_nT() const { return magnetic_field_i_nT_; } + inline libra::Vector<3> GetGeomagneticFieldneticField_i_nT() const { return magnetic_field_i_nT_; } /** - * @fn GetMagneticField_b_nT + * @fn GetGeomagneticFieldneticField_b_nT * @brief Return magnetic field vector in the body fixed frame [nT] */ - inline libra::Vector<3> GetMagneticField_b_nT() const { return magnetic_field_b_nT_; } + inline libra::Vector<3> GetGeomagneticFieldneticField_b_nT() const { return magnetic_field_b_nT_; } // Override ILoggable /** diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 6ed3bfe41..94737b8d6 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -62,20 +62,20 @@ class LocalEnvironment { */ inline const Atmosphere& GetAtmosphere() const { return *atmosphere_; } /** - * @fn GetMag + * @fn GetGeomagneticField * @brief Return GeomagneticField class */ - inline const GeomagneticField& GetMag() const { return *geomagnetic_field_; } + inline const GeomagneticField& GetGeomagneticField() const { return *geomagnetic_field_; } /** - * @fn GetSrp + * @fn GetSolarRadiationPressure * @brief Return SRPEnvironment class */ - inline const SRPEnvironment& GetSrp() const { return *solar_radiation_pressure_environment_; } + inline const SRPEnvironment& GetSolarRadiationPressure() const { return *solar_radiation_pressure_environment_; } /** - * @fn GetCelesInfo + * @fn GetCelestialInformation * @brief Return LocalCelestialInformation class */ - inline const LocalCelestialInformation& GetCelesInfo() const { return *celestial_information_; } + inline const LocalCelestialInformation& GetCelestialInformation() const { return *celestial_information_; } private: Atmosphere* atmosphere_; //!< Atmospheric density of the earth diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index a93be745d..d5f82bb6f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -32,8 +32,8 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // MagSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - mag_sensor_ = new MagSensor( - InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetMag()))); + mag_sensor_ = new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + &(local_env_->GetGeomagneticField()))); // STT ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); @@ -44,7 +44,8 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_env_->GetSrp()), &(local_env_->GetCelesInfo()))); + sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_env_->GetSolarRadiationPressure()), + &(local_env_->GetCelestialInformation()))); // GNSS-R ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); @@ -55,8 +56,8 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // MagTorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDir(ini_path); - mag_torquer_ = new MagTorquer( - InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetMag()))); + mag_torquer_ = new MagTorquer(InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + &(local_env_->GetGeomagneticField()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 04801e39d..ece00aecf 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -32,7 +32,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen clock_gen_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelesInfo()), sat_id, structure_); + dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); @@ -44,7 +44,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen clock_gen_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelesInfo()), sat_id, structure_, rel_info); + dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_, rel_info); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); @@ -80,7 +80,7 @@ void Spacecraft::Update(const SimTime* sim_time) { dynamics_->AddForce_b(components_->GenerateForce_N_b()); // Propagate dynamics - dynamics_->Update(sim_time, &(local_env_->GetCelesInfo())); + dynamics_->Update(sim_time, &(local_env_->GetCelestialInformation())); } void Spacecraft::Clear(void) { dynamics_->ClearForceTorque(); } From 1967fc6c5652da88cda05e0eaa3ba509399a0afb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:54:09 +0100 Subject: [PATCH 0549/1086] Move to private --- src/environment/local/local_environment.hpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 94737b8d6..8f6b9fd13 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -33,14 +33,6 @@ class LocalEnvironment { * @brief Destructor */ ~LocalEnvironment(); - /** - * @fn Initialize - * @brief Initialize function - * @param [in] simulation_configuration: Simulation configuration - * @param [in] global_environment: Global environment - * @param [in] spacecraft_id: Satellite ID - */ - void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Update @@ -82,6 +74,15 @@ class LocalEnvironment { GeomagneticField* geomagnetic_field_; //!< Magnetic field of the earth SRPEnvironment* solar_radiation_pressure_environment_; //!< Solar radiation pressure LocalCelestialInformation* celestial_information_; //!< Celestial information + + /** + * @fn Initialize + * @brief Initialize function + * @param [in] simulation_configuration: Simulation configuration + * @param [in] global_environment: Global environment + * @param [in] spacecraft_id: Satellite ID + */ + void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); }; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ From 9a3f6b3159991e47f1744b045414b5252a69626a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:57:13 +0100 Subject: [PATCH 0550/1086] Remove using --- .../solar_radiation_pressure_environment.cpp | 28 +++++++++---------- .../solar_radiation_pressure_environment.hpp | 7 ++--- 2 files changed, 15 insertions(+), 20 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 25df58e19..0989d7c28 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -6,14 +6,12 @@ #include #include -#include #include -#include -#include -#include -using libra::Vector; -using namespace std; +#include "environment/global/physical_constants.hpp" +#include "library/logger/log_utility.hpp" +#include "library/math/constants.hpp" +#include "library/math/vector.hpp" SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : local_celes_info_(local_celes_info) { solar_constant_ = 1366.0; // [W/m2] @@ -30,7 +28,7 @@ void SRPEnvironment::UpdateAllStates() { } void SRPEnvironment::UpdatePressure() { - const Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); + const libra::Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); const double distance_sat_to_sun = norm(r_sc2sun_eci); pressure_ = solar_constant_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } @@ -45,8 +43,8 @@ double SRPEnvironment::GetSolarConstant() const { return solar_constant_; } double SRPEnvironment::GetShadowCoefficient() const { return shadow_coefficient_; } -string SRPEnvironment::GetLogHeader() const { - string str_tmp = ""; +std::string SRPEnvironment::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteScalar("solar_radiation_pressure_at_spacecraft_position", "N/m2"); str_tmp += WriteScalar("shadow_coefficient_at_spacecraft_position"); @@ -54,8 +52,8 @@ string SRPEnvironment::GetLogHeader() const { return str_tmp; } -string SRPEnvironment::GetLogValue() const { - string str_tmp = ""; +std::string SRPEnvironment::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteScalar(pressure_ * shadow_coefficient_); str_tmp += WriteScalar(shadow_coefficient_); @@ -63,14 +61,14 @@ string SRPEnvironment::GetLogValue() const { return str_tmp; } -void SRPEnvironment::CalcShadowCoefficient(string shadow_source_name) { +void SRPEnvironment::CalcShadowCoefficient(std::string shadow_source_name) { if (shadow_source_name == "SUN") { shadow_coefficient_ = 1.0; return; } - const Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); - const Vector<3> r_sc2source_eci = local_celes_info_->GetPositionFromSpacecraft_i_m(shadow_source_name.c_str()); + const libra::Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); + const libra::Vector<3> r_sc2source_eci = local_celes_info_->GetPositionFromSpacecraft_i_m(shadow_source_name.c_str()); const double shadow_source_radius_m = local_celes_info_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); @@ -84,7 +82,7 @@ void SRPEnvironment::CalcShadowCoefficient(string shadow_source_name) { // The angle between the center of the sun and the common chord const double x = (delta * delta + sd_sun * sd_sun - sd_source * sd_source) / (2.0 * delta); // The length of the common chord of the apparent solar disk and apparent telestial disk - const double y = sqrt(max(sd_sun * sd_sun - x * x, 0.0)); + const double y = sqrt(std::max(sd_sun * sd_sun - x * x, 0.0)); const double a = sd_sun; const double b = sd_source; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 2304dda9e..dac2f3518 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,11 +6,8 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ -#include -#include -#include - -using libra::Vector; +#include "environment/local/local_celestial_information.hpp" +#include "library/logger/loggable.hpp" /** * @class SRPEnvironment From 39fd563f24b91268a7a58450dc4ff42ff61dfa10 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 14:57:37 +0100 Subject: [PATCH 0551/1086] Remove old comments --- .../solar_radiation_pressure_environment.cpp | 28 ------------------- 1 file changed, 28 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 0989d7c28..9d1ca317a 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -103,31 +103,3 @@ void SRPEnvironment::CalcShadowCoefficient(std::string shadow_source_name) { shadow_coefficient_ = 1.0; } } - -/*int main(){ - Vector<3> ep; - Vector<3> sp; - ofstream log1;//ファイル書き込み用 - log1.open("log1.csv",ios::trunc); - ofstream log2;//ファイル書き込み用 - log2.open("log2.csv",ios::trunc); - sp[0] = 149597870700.0; - sp[1] = 0; - sp[2] = 0; - ep[0] = 6400000; - ep[1] = 0; - ep[2] = 0; - SRPEnvironment srp; - for(long i = 6400000;i < 4200000000; i = i + 10000000){ - sp[0] = 149597870700.0 + double(i); - ep[0] = double(i); - srp.Update(ep,sp); - log1 << srp.GetP() << ","; - } - for(int i = 0;i < 360; i++){ - ep[0] = 6400000 * cos(libra::pi * i / 180); - ep[1] = 6400000 * sin(libra::pi * i / 180); - srp.Update(ep,sp); - log2 << srp.GetP() << ","; - } -}*/ From c5a0d338ed0d817ae37c18b50b5701c68f9e054a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:01:33 +0100 Subject: [PATCH 0552/1086] Fix private variables name --- .../solar_radiation_pressure_environment.cpp | 33 ++++++++++--------- .../solar_radiation_pressure_environment.hpp | 12 +++---- 2 files changed, 23 insertions(+), 22 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 9d1ca317a..e30b58f33 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -13,11 +13,11 @@ #include "library/math/constants.hpp" #include "library/math/vector.hpp" -SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : local_celes_info_(local_celes_info) { - solar_constant_ = 1366.0; // [W/m2] - pressure_ = solar_constant_ / environment::speed_of_light_m_s; // [N/m2] - shadow_source_name_ = local_celes_info_->GetGlobalInformation().GetCenterBodyName(); - sun_radius_m_ = local_celes_info_->GetGlobalInformation().GetMeanRadiusFromName_m("SUN"); +SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : local_celestial_information_(local_celes_info) { + solar_constant_W_m2_ = 1366.0; // [W/m2] + solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s; // [N/m2] + shadow_source_name_ = local_celestial_information_->GetGlobalInformation().GetCenterBodyName(); + sun_radius_m_ = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m("SUN"); } void SRPEnvironment::UpdateAllStates() { @@ -28,25 +28,26 @@ void SRPEnvironment::UpdateAllStates() { } void SRPEnvironment::UpdatePressure() { - const libra::Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); + const libra::Vector<3> r_sc2sun_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); const double distance_sat_to_sun = norm(r_sc2sun_eci); - pressure_ = solar_constant_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); + solar_radiation_pressure_N_m2_ = + solar_constant_W_m2_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } -double SRPEnvironment::CalcTruePressure() const { return pressure_ * shadow_coefficient_; } +double SRPEnvironment::CalcTruePressure() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } -double SRPEnvironment::CalcPowerDensity() const { return pressure_ * environment::speed_of_light_m_s * shadow_coefficient_; } +double SRPEnvironment::CalcPowerDensity() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } -double SRPEnvironment::GetPressure() const { return pressure_; } +double SRPEnvironment::GetPressure() const { return solar_radiation_pressure_N_m2_; } -double SRPEnvironment::GetSolarConstant() const { return solar_constant_; } +double SRPEnvironment::GetSolarConstant() const { return solar_constant_W_m2_; } double SRPEnvironment::GetShadowCoefficient() const { return shadow_coefficient_; } std::string SRPEnvironment::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("solar_radiation_pressure_at_spacecraft_position", "N/m2"); + str_tmp += WriteScalar("solar_radiation_solar_radiation_pressure_N_m2_at_spacecraft_position", "N/m2"); str_tmp += WriteScalar("shadow_coefficient_at_spacecraft_position"); return str_tmp; @@ -55,7 +56,7 @@ std::string SRPEnvironment::GetLogHeader() const { std::string SRPEnvironment::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(pressure_ * shadow_coefficient_); + str_tmp += WriteScalar(solar_radiation_pressure_N_m2_ * shadow_coefficient_); str_tmp += WriteScalar(shadow_coefficient_); return str_tmp; @@ -67,10 +68,10 @@ void SRPEnvironment::CalcShadowCoefficient(std::string shadow_source_name) { return; } - const libra::Vector<3> r_sc2sun_eci = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); - const libra::Vector<3> r_sc2source_eci = local_celes_info_->GetPositionFromSpacecraft_i_m(shadow_source_name.c_str()); + const libra::Vector<3> r_sc2sun_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); + const libra::Vector<3> r_sc2source_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m(shadow_source_name.c_str()); - const double shadow_source_radius_m = local_celes_info_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); + const double shadow_source_radius_m = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); const double distance_sat_to_sun = norm(r_sc2sun_eci); const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index dac2f3518..a5dc88579 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -84,13 +84,13 @@ class SRPEnvironment : public ILoggable { virtual std::string GetLogValue() const; private: - double pressure_; //!< Solar radiation pressure [N/m^2] - double solar_constant_; //!< solar constant [W/m^2] TODO: We need to change the value depends on sun activity. - double shadow_coefficient_ = 1.0; //!< shadow function - double sun_radius_m_; //!< Sun radius [m] - std::string shadow_source_name_; //!< Shadow source name + double solar_radiation_pressure_N_m2_; //!< Solar radiation pressure [N/m^2] + double solar_constant_W_m2_; //!< solar constant [W/m^2] TODO: We need to change the value depends on sun activity. + double shadow_coefficient_ = 1.0; //!< shadow function + double sun_radius_m_; //!< Sun radius [m] + std::string shadow_source_name_; //!< Shadow source name - LocalCelestialInformation* local_celes_info_; //!< Local celestial information + LocalCelestialInformation* local_celestial_information_; //!< Local celestial information /** * @fn CalcShadowCoefficient From 36f042277d9290281bf39f4bd7ad166dd43c4cbe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:01:51 +0100 Subject: [PATCH 0553/1086] Fix comments --- .../local/solar_radiation_pressure_environment.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index a5dc88579..f09d26bf3 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -85,8 +85,8 @@ class SRPEnvironment : public ILoggable { private: double solar_radiation_pressure_N_m2_; //!< Solar radiation pressure [N/m^2] - double solar_constant_W_m2_; //!< solar constant [W/m^2] TODO: We need to change the value depends on sun activity. - double shadow_coefficient_ = 1.0; //!< shadow function + double solar_constant_W_m2_; //!< Solar constant [W/m^2] TODO: We need to change the value depends on sun activity. + double shadow_coefficient_ = 1.0; //!< Shadow function double sun_radius_m_; //!< Sun radius [m] std::string shadow_source_name_; //!< Shadow source name From 24a1070688b97eb1df7bc8efa226244a5ec1312d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:08:11 +0100 Subject: [PATCH 0554/1086] Move to inline functions --- .../local/solar_radiation_pressure_environment.cpp | 11 ----------- .../local/solar_radiation_pressure_environment.hpp | 14 ++++++++------ 2 files changed, 8 insertions(+), 17 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index e30b58f33..e959448eb 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -8,7 +8,6 @@ #include #include -#include "environment/global/physical_constants.hpp" #include "library/logger/log_utility.hpp" #include "library/math/constants.hpp" #include "library/math/vector.hpp" @@ -34,16 +33,6 @@ void SRPEnvironment::UpdatePressure() { solar_constant_W_m2_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } -double SRPEnvironment::CalcTruePressure() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } - -double SRPEnvironment::CalcPowerDensity() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } - -double SRPEnvironment::GetPressure() const { return solar_radiation_pressure_N_m2_; } - -double SRPEnvironment::GetSolarConstant() const { return solar_constant_W_m2_; } - -double SRPEnvironment::GetShadowCoefficient() const { return shadow_coefficient_; } - std::string SRPEnvironment::GetLogHeader() const { std::string str_tmp = ""; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index f09d26bf3..059bb3088 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -6,8 +6,8 @@ #ifndef S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ #define S2E_ENVIRONMENT_LOCAL_SOLAR_RADIATION_PRESSURE_ENVIRONMENT_HPP_ +#include "environment/global/physical_constants.hpp" #include "environment/local/local_celestial_information.hpp" -#include "library/logger/loggable.hpp" /** * @class SRPEnvironment @@ -44,27 +44,29 @@ class SRPEnvironment : public ILoggable { * @fn CalcTruePressure * @brief Calculate and return solar radiation pressure that takes into account eclipse [N/m^2] */ - double CalcTruePressure() const; + inline double CalcTruePressure() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } /** * @fn CalcPowerDensity * @brief Calculate and return solar power per unit area considering eclipse [W/m^2] */ - double CalcPowerDensity() const; + inline double CalcPowerDensity() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } + + // Getter /** * @fn GetPressure * @brief Return solar pressure without eclipse effect [N/m^2] */ - double GetPressure() const; + inline double GetPressure() const { return solar_radiation_pressure_N_m2_; } /** * @fn GetSolarConstant * @brief Return solar constant value [W/m^2] */ - double GetSolarConstant() const; + inline double GetSolarConstant() const { return solar_constant_W_m2_; } /** * @fn GetShadowCoefficient * @brief Return shadow function */ - double GetShadowCoefficient() const; + inline double GetShadowCoefficient() const { return shadow_coefficient_; } /** * @fn GetIsEclipsed * @brief Returns true if the shadow function is less than 1 From 3f9310ee243daacd9f5364b49e581005f8a7a737 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:09:04 +0100 Subject: [PATCH 0555/1086] Fix function argument name --- .../local/solar_radiation_pressure_environment.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index e959448eb..d0d5ccd1b 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -12,7 +12,7 @@ #include "library/math/constants.hpp" #include "library/math/vector.hpp" -SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celes_info) : local_celestial_information_(local_celes_info) { +SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celestial_information) : local_celestial_information_(local_celestial_information) { solar_constant_W_m2_ = 1366.0; // [W/m2] solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s; // [N/m2] shadow_source_name_ = local_celestial_information_->GetGlobalInformation().GetCenterBodyName(); diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 059bb3088..b8b32cdfb 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -20,9 +20,9 @@ class SRPEnvironment : public ILoggable { /** * @fn SRPEnvironment * @brief Constructor - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information */ - SRPEnvironment(LocalCelestialInformation* local_celes_info); + SRPEnvironment(LocalCelestialInformation* local_celestial_information); /** * @fn ~SRPEnvironment * @brief Destructor From abfc0dc375741ce74ef19295ca56698a7d31803f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:12:26 +0100 Subject: [PATCH 0556/1086] Fix initialize --- .../local/solar_radiation_pressure_environment.cpp | 5 ++--- .../local/solar_radiation_pressure_environment.hpp | 2 +- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index d0d5ccd1b..b8f89e90c 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -13,8 +13,7 @@ #include "library/math/vector.hpp" SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celestial_information) : local_celestial_information_(local_celestial_information) { - solar_constant_W_m2_ = 1366.0; // [W/m2] - solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s; // [N/m2] + solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s; shadow_source_name_ = local_celestial_information_->GetGlobalInformation().GetCenterBodyName(); sun_radius_m_ = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m("SUN"); } @@ -36,7 +35,7 @@ void SRPEnvironment::UpdatePressure() { std::string SRPEnvironment::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("solar_radiation_solar_radiation_pressure_N_m2_at_spacecraft_position", "N/m2"); + str_tmp += WriteScalar("solar_radiation_pressure_at_spacecraft_position", "N/m2"); str_tmp += WriteScalar("shadow_coefficient_at_spacecraft_position"); return str_tmp; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index b8b32cdfb..b8e83b6a9 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -87,7 +87,7 @@ class SRPEnvironment : public ILoggable { private: double solar_radiation_pressure_N_m2_; //!< Solar radiation pressure [N/m^2] - double solar_constant_W_m2_; //!< Solar constant [W/m^2] TODO: We need to change the value depends on sun activity. + double solar_constant_W_m2_ = 1366.0; //!< Solar constant [W/m^2] TODO: We need to change the value depends on sun activity. double shadow_coefficient_ = 1.0; //!< Shadow function double sun_radius_m_; //!< Sun radius [m] std::string shadow_source_name_; //!< Shadow source name From e37fb4b22fdc8aef2b4b51af6b3063b2f398a14c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:13:18 +0100 Subject: [PATCH 0557/1086] Move to private function --- .../local/solar_radiation_pressure_environment.hpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index b8e83b6a9..2655313c5 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -34,11 +34,6 @@ class SRPEnvironment : public ILoggable { * @brief Update pressure and shadow coefficients */ void UpdateAllStates(); - /** - * @fn UpdatePressure - * @brief Update pressure with solar distance - */ - void UpdatePressure(); /** * @fn CalcTruePressure @@ -94,6 +89,12 @@ class SRPEnvironment : public ILoggable { LocalCelestialInformation* local_celestial_information_; //!< Local celestial information + /** + * @fn UpdatePressure + * @brief Update pressure with solar distance + */ + void UpdatePressure(); + /** * @fn CalcShadowCoefficient * @brief Calculate shadow coefficient From 720000aba0890a87565a3f48d71c6714536b36cf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:23:34 +0100 Subject: [PATCH 0558/1086] Fix public function name --- src/components/real/aocs/sun_sensor.cpp | 4 ++-- .../real/power/solar_array_panel.cpp | 4 ++-- .../solar_radiation_pressure_disturbance.cpp | 2 +- .../solar_radiation_pressure_environment.hpp | 22 +++++++++---------- 4 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 276ddab37..1c6a1085e 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -97,7 +97,7 @@ void SunSensor::SunDetectionJudgement() { double sun_angle_ = acos(sun_direction_c[2]); - if (solar_illuminance_ < intensity_lower_threshold_percent_ / 100.0 * srp_->GetSolarConstant()) { + if (solar_illuminance_ < intensity_lower_threshold_percent_ / 100.0 * srp_->GetSolarConstant_W_m2()) { sun_detected_flag_ = false; } else { if (sun_angle_ < detectable_angle_rad_) { @@ -117,7 +117,7 @@ void SunSensor::CalcSolarIlluminance() { return; } - double power_density = srp_->CalcPowerDensity(); + double power_density = srp_->CalcPowerDensity_W_m2(); solar_illuminance_ = power_density * cos(sun_angle_); // TODO: Take into account the effects of albedo. } diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index d21b2d556..51852a700 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -97,13 +97,13 @@ std::string SAP::GetLogValue() const { void SAP::MainRoutine(int time_count) { if (CsvScenarioInterface::IsCsvScenarioEnabled()) { double time_query = compo_step_time_ * time_count; - const auto solar_constant = srp_->GetSolarConstant(); + const auto solar_constant = srp_->GetSolarConstant_W_m2(); libra::Vector<3> sun_direction_body = CsvScenarioInterface::GetSunDirectionBody(time_query); libra::Vector<3> normalized_sun_direction_body = libra::normalize(sun_direction_body); power_generation_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * cell_area_ * number_of_parallel_ * number_of_series_ * inner_product(normal_vector_, normalized_sun_direction_body); } else { - const auto power_density = srp_->CalcPowerDensity(); + const auto power_density = srp_->CalcPowerDensity_W_m2(); libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = libra::normalize(sun_pos_b); power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 24a2e0bfa..de2c1c137 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -16,7 +16,7 @@ void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& d UNUSED(dynamics); libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); - CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().CalcTruePressure()); + CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().GetPressure_Nm2()); } void SolarRadiation::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 2655313c5..c77bf6d6d 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -36,27 +36,27 @@ class SRPEnvironment : public ILoggable { void UpdateAllStates(); /** - * @fn CalcTruePressure - * @brief Calculate and return solar radiation pressure that takes into account eclipse [N/m^2] - */ - inline double CalcTruePressure() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } - /** - * @fn CalcPowerDensity + * @fn CalcPowerDensity_W_m2 * @brief Calculate and return solar power per unit area considering eclipse [W/m^2] */ - inline double CalcPowerDensity() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } + inline double CalcPowerDensity_W_m2() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } // Getter /** - * @fn GetPressure + * @fn GetPressure_Nm2 + * @brief Calculate and return solar radiation pressure that takes into account eclipse [N/m^2] + */ + inline double GetPressure_Nm2() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } + /** + * @fn GetPressureWithoutEclipse_Nm2 * @brief Return solar pressure without eclipse effect [N/m^2] */ - inline double GetPressure() const { return solar_radiation_pressure_N_m2_; } + inline double GetPressureWithoutEclipse_Nm2() const { return solar_radiation_pressure_N_m2_; } /** - * @fn GetSolarConstant + * @fn GetSolarConstant_W_m2 * @brief Return solar constant value [W/m^2] */ - inline double GetSolarConstant() const { return solar_constant_W_m2_; } + inline double GetSolarConstant_W_m2() const { return solar_constant_W_m2_; } /** * @fn GetShadowCoefficient * @brief Return shadow function From c45fc7beea6116380920bbe1b17f51cf2d1cdbd5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:24:29 +0100 Subject: [PATCH 0559/1086] Fix public function name --- src/components/real/aocs/sun_sensor.cpp | 2 +- src/components/real/power/solar_array_panel.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 11 +++++------ 3 files changed, 7 insertions(+), 8 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 1c6a1085e..7c0234728 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -117,7 +117,7 @@ void SunSensor::CalcSolarIlluminance() { return; } - double power_density = srp_->CalcPowerDensity_W_m2(); + double power_density = srp_->GetPowerDensity_W_m2(); solar_illuminance_ = power_density * cos(sun_angle_); // TODO: Take into account the effects of albedo. } diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 51852a700..2af4ff466 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -103,7 +103,7 @@ void SAP::MainRoutine(int time_count) { power_generation_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * cell_area_ * number_of_parallel_ * number_of_series_ * inner_product(normal_vector_, normalized_sun_direction_body); } else { - const auto power_density = srp_->CalcPowerDensity_W_m2(); + const auto power_density = srp_->GetPowerDensity_W_m2(); libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = libra::normalize(sun_pos_b); power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index c77bf6d6d..4df662624 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -35,18 +35,17 @@ class SRPEnvironment : public ILoggable { */ void UpdateAllStates(); - /** - * @fn CalcPowerDensity_W_m2 - * @brief Calculate and return solar power per unit area considering eclipse [W/m^2] - */ - inline double CalcPowerDensity_W_m2() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } - // Getter /** * @fn GetPressure_Nm2 * @brief Calculate and return solar radiation pressure that takes into account eclipse [N/m^2] */ inline double GetPressure_Nm2() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } + /** + * @fn GetPowerDensity_W_m2 + * @brief Calculate and return solar power per unit area considering eclipse [W/m^2] + */ + inline double GetPowerDensity_W_m2() const { return solar_radiation_pressure_N_m2_ * environment::speed_of_light_m_s * shadow_coefficient_; } /** * @fn GetPressureWithoutEclipse_Nm2 * @brief Return solar pressure without eclipse effect [N/m^2] From 38f349aa95a48ca22162937c6ced232fa2c8320e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:25:17 +0100 Subject: [PATCH 0560/1086] Rename SRPEnvironment to SolarRadiationPressureEnvironment --- src/components/real/aocs/initialize_sun_sensor.cpp | 4 ++-- src/components/real/aocs/initialize_sun_sensor.hpp | 6 +++--- src/components/real/aocs/sun_sensor.cpp | 5 +++-- src/components/real/aocs/sun_sensor.hpp | 9 +++++---- .../real/power/initialize_solar_array_panel.cpp | 4 ++-- .../real/power/initialize_solar_array_panel.hpp | 4 ++-- src/components/real/power/solar_array_panel.cpp | 8 +++++--- src/components/real/power/solar_array_panel.hpp | 14 ++++++++------ .../local/initialize_local_environment.cpp | 5 +++-- .../local/initialize_local_environment.hpp | 5 +++-- src/environment/local/local_environment.cpp | 3 ++- src/environment/local/local_environment.hpp | 12 ++++++------ .../local/solar_radiation_pressure_environment.cpp | 13 +++++++------ .../local/solar_radiation_pressure_environment.hpp | 12 ++++++------ 14 files changed, 57 insertions(+), 47 deletions(-) diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index 0488b67d6..ca95703e5 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SRPEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; @@ -43,7 +43,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n return ss; } -SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, const SRPEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index b67f9a119..ee47f9aa9 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -17,7 +17,7 @@ * @param [in] srp: Solar radiation pressure environment * @param [in] local_env: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const SRPEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** * @fn InitSunSensor @@ -29,7 +29,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::str * @param [in] srp: Solar radiation pressure environment * @param [in] local_env: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, const SRPEnvironment* srp, - const LocalCelestialInformation* local_celes_info); +SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 7c0234728..6dfb525f3 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -15,7 +15,7 @@ using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, - const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : ComponentBase(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), @@ -28,7 +28,8 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int i SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, - const double intensity_lower_threshold_percent, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) + const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info) : ComponentBase(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 77a6fd9be..bf94398a6 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -36,8 +36,8 @@ class SunSensor : public ComponentBase, public ILoggable { * @param [in] local_celes_info: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, - const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SRPEnvironment* srp, - const LocalCelestialInformation* local_celes_info); + const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** * @fn SunSensor * @brief Constructor with power port @@ -55,7 +55,8 @@ class SunSensor : public ComponentBase, public ILoggable { */ SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, - const double intensity_lower_threshold_percent, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info); + const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info); // Override functions for ComponentBase /** @@ -104,7 +105,7 @@ class SunSensor : public ComponentBase, public ILoggable { double bias_beta_ = 0.0; //!< Constant bias for beta angle (Value is calculated by random number generator) // Measured variables - const SRPEnvironment* srp_; //!< Solar Radiation Pressure environment + const SolarRadiationPressureEnvironment* srp_; //!< Solar Radiation Pressure environment const LocalCelestialInformation* local_celes_info_; //!< Local celestial information // functions diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index d2bf85ea8..692d8f031 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -9,7 +9,7 @@ #include "library/initialize/initialize_file_access.hpp" -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { IniAccess sap_conf(fname); @@ -46,7 +46,7 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons return sap; } -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time) { +SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, double compo_step_time) { IniAccess sap_conf(fname); const std::string st_sap_id = std::to_string(sap_id); diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index 878b3a25a..8992af598 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -18,7 +18,7 @@ * @param [in] local_celes_info: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time); /* @@ -30,6 +30,6 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons * @param [in] srp: Solar Radiation Pressure environment * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SRPEnvironment* srp, double compo_step_time); +SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 2af4ff466..1684093c0 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -9,7 +9,7 @@ #include SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) : ComponentBase(prescaler, clock_gen), id_(id), @@ -27,7 +27,8 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s } SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, double compo_step_time) + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, + double compo_step_time) : ComponentBase(prescaler, clock_gen), id_(id), number_of_series_(number_of_series), @@ -43,7 +44,8 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s } SAP::SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, - double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info) + double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info) : ComponentBase(10, clock_gen), id_(id), number_of_series_(number_of_series), diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 3414322bd..4592b05e5 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -32,7 +32,7 @@ class SAP : public ComponentBase, public ILoggable { * @param [in] compo_step_time: Component step time [sec] */ SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time); /** * @fn SAP @@ -50,7 +50,8 @@ class SAP : public ComponentBase, public ILoggable { * @param [in] compo_step_time: Component step time [sec] */ SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, double compo_step_time); + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, + double compo_step_time); /** * @fn SAP * @brief Constructor without prescaler @@ -67,7 +68,8 @@ class SAP : public ComponentBase, public ILoggable { * @param [in] local_celes_info: Local celestial information */ SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, - double cell_efficiency, double transmission_efficiency, const SRPEnvironment* srp, const LocalCelestialInformation* local_celes_info); + double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info); /** * @fn SAP * @brief Copy constructor @@ -111,13 +113,13 @@ class SAP : public ComponentBase, public ILoggable { const double cell_efficiency_; //!< Power generation efficiency of solar cell const double transmission_efficiency_; //!< Efficiency of transmission to PCU - const SRPEnvironment* const srp_; //!< Solar Radiation Pressure environment - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information + const SolarRadiationPressureEnvironment* const srp_; //!< Solar Radiation Pressure environment + const LocalCelestialInformation* local_celes_info_; //!< Local celestial information double voltage_; //!< Voltage [V] double power_generation_; //!< Generated power [W] - static const double solar_constant_; //!< Solar constant TODO: Use SRPEnvironment? + static const double solar_constant_; //!< Solar constant TODO: Use SolarRadiationPressureEnvironment? static const double light_speed_; //!< Speed of light TODO: Use PhysicalConstant? double compo_step_time_; //!< Component step time [sec] diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index b7f986c26..20d325572 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -27,11 +27,12 @@ GeomagneticField InitGeomagneticField(std::string initialize_file_path) { return mag_env; } -SRPEnvironment InitSRPEnvironment(std::string initialize_file_path, LocalCelestialInformation* local_celestial_information) { +SolarRadiationPressureEnvironment InitSolarRadiationPressureEnvironment(std::string initialize_file_path, + LocalCelestialInformation* local_celestial_information) { auto conf = IniAccess(initialize_file_path); const char* section = "SOLAR_RADIATION_PRESSURE_ENVIRONMENT"; - SRPEnvironment srp_env(local_celestial_information); + SolarRadiationPressureEnvironment srp_env(local_celestial_information); srp_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); srp_env.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); diff --git a/src/environment/local/initialize_local_environment.hpp b/src/environment/local/initialize_local_environment.hpp index f18a8883e..0fa861a36 100644 --- a/src/environment/local/initialize_local_environment.hpp +++ b/src/environment/local/initialize_local_environment.hpp @@ -17,12 +17,13 @@ */ GeomagneticField InitGeomagneticField(std::string initialize_file_path); /** - * @fn InitSRPEnvironment + * @fn InitSolarRadiationPressureEnvironment * @brief Initialize solar radiation pressure * @param [in] initialize_file_path: Path to initialize file * @param [in] local_celestial_information: Local celestial information */ -SRPEnvironment InitSRPEnvironment(std::string initialize_file_path, LocalCelestialInformation* local_celestial_information); +SolarRadiationPressureEnvironment InitSolarRadiationPressureEnvironment(std::string initialize_file_path, + LocalCelestialInformation* local_celestial_information); /** * @fn InitAtmosphere * @brief Initialize atmospheric density of the earth diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index fd4d9ab8d..159e7ecc3 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -34,7 +34,8 @@ void LocalEnvironment::Initialize(const SimulationConfig* simulation_configurati geomagnetic_field_ = new GeomagneticField(InitGeomagneticField(ini_fname)); atmosphere_ = new Atmosphere(InitAtmosphere(ini_fname)); celestial_information_ = new LocalCelestialInformation(&(global_environment->GetCelestialInformation())); - solar_radiation_pressure_environment_ = new SRPEnvironment(InitSRPEnvironment(ini_fname, celestial_information_)); + solar_radiation_pressure_environment_ = + new SolarRadiationPressureEnvironment(InitSolarRadiationPressureEnvironment(ini_fname, celestial_information_)); // Force to disable when the center body is not the Earth if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") { diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 8f6b9fd13..240334e1d 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -60,9 +60,9 @@ class LocalEnvironment { inline const GeomagneticField& GetGeomagneticField() const { return *geomagnetic_field_; } /** * @fn GetSolarRadiationPressure - * @brief Return SRPEnvironment class + * @brief Return SolarRadiationPressureEnvironment class */ - inline const SRPEnvironment& GetSolarRadiationPressure() const { return *solar_radiation_pressure_environment_; } + inline const SolarRadiationPressureEnvironment& GetSolarRadiationPressure() const { return *solar_radiation_pressure_environment_; } /** * @fn GetCelestialInformation * @brief Return LocalCelestialInformation class @@ -70,10 +70,10 @@ class LocalEnvironment { inline const LocalCelestialInformation& GetCelestialInformation() const { return *celestial_information_; } private: - Atmosphere* atmosphere_; //!< Atmospheric density of the earth - GeomagneticField* geomagnetic_field_; //!< Magnetic field of the earth - SRPEnvironment* solar_radiation_pressure_environment_; //!< Solar radiation pressure - LocalCelestialInformation* celestial_information_; //!< Celestial information + Atmosphere* atmosphere_; //!< Atmospheric density of the earth + GeomagneticField* geomagnetic_field_; //!< Magnetic field of the earth + SolarRadiationPressureEnvironment* solar_radiation_pressure_environment_; //!< Solar radiation pressure + LocalCelestialInformation* celestial_information_; //!< Celestial information /** * @fn Initialize diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index b8f89e90c..271ecb1f6 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -12,27 +12,28 @@ #include "library/math/constants.hpp" #include "library/math/vector.hpp" -SRPEnvironment::SRPEnvironment(LocalCelestialInformation* local_celestial_information) : local_celestial_information_(local_celestial_information) { +SolarRadiationPressureEnvironment::SolarRadiationPressureEnvironment(LocalCelestialInformation* local_celestial_information) + : local_celestial_information_(local_celestial_information) { solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s; shadow_source_name_ = local_celestial_information_->GetGlobalInformation().GetCenterBodyName(); sun_radius_m_ = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m("SUN"); } -void SRPEnvironment::UpdateAllStates() { +void SolarRadiationPressureEnvironment::UpdateAllStates() { if (!IsCalcEnabled) return; UpdatePressure(); CalcShadowCoefficient(shadow_source_name_); } -void SRPEnvironment::UpdatePressure() { +void SolarRadiationPressureEnvironment::UpdatePressure() { const libra::Vector<3> r_sc2sun_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); const double distance_sat_to_sun = norm(r_sc2sun_eci); solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } -std::string SRPEnvironment::GetLogHeader() const { +std::string SolarRadiationPressureEnvironment::GetLogHeader() const { std::string str_tmp = ""; str_tmp += WriteScalar("solar_radiation_pressure_at_spacecraft_position", "N/m2"); @@ -41,7 +42,7 @@ std::string SRPEnvironment::GetLogHeader() const { return str_tmp; } -std::string SRPEnvironment::GetLogValue() const { +std::string SolarRadiationPressureEnvironment::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(solar_radiation_pressure_N_m2_ * shadow_coefficient_); @@ -50,7 +51,7 @@ std::string SRPEnvironment::GetLogValue() const { return str_tmp; } -void SRPEnvironment::CalcShadowCoefficient(std::string shadow_source_name) { +void SolarRadiationPressureEnvironment::CalcShadowCoefficient(std::string shadow_source_name) { if (shadow_source_name == "SUN") { shadow_coefficient_ = 1.0; return; diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 4df662624..3a3576491 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -10,24 +10,24 @@ #include "environment/local/local_celestial_information.hpp" /** - * @class SRPEnvironment + * @class SolarRadiationPressureEnvironment * @brief Class to calculate Solar Radiation Pressure */ -class SRPEnvironment : public ILoggable { +class SolarRadiationPressureEnvironment : public ILoggable { public: bool IsCalcEnabled = true; //!< Calculation flag /** - * @fn SRPEnvironment + * @fn SolarRadiationPressureEnvironment * @brief Constructor * @param [in] local_celestial_information: Local celestial information */ - SRPEnvironment(LocalCelestialInformation* local_celestial_information); + SolarRadiationPressureEnvironment(LocalCelestialInformation* local_celestial_information); /** - * @fn ~SRPEnvironment + * @fn ~SolarRadiationPressureEnvironment * @brief Destructor */ - virtual ~SRPEnvironment() {} + virtual ~SolarRadiationPressureEnvironment() {} /** * @fn UpdateAllStates From 85be7318b73703e5d010d7ba8d895a4a6e0a1a4c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:31:32 +0100 Subject: [PATCH 0561/1086] Rename MagDisturbance and SolarRadiation --- src/components/real/aocs/gnss_receiver.cpp | 4 +-- src/components/real/aocs/gnss_receiver.hpp | 6 ++-- .../real/aocs/initialize_gnss_receiver.cpp | 4 +-- .../real/aocs/initialize_gnss_receiver.hpp | 4 +-- .../real/power/pcu_initial_study.cpp | 2 +- src/disturbances/disturbances.cpp | 6 ++-- src/disturbances/disturbances.hpp | 2 +- src/disturbances/initialize_disturbances.cpp | 10 +++---- src/disturbances/initialize_disturbances.hpp | 10 +++---- src/disturbances/magnetic_disturbance.cpp | 12 ++++---- src/disturbances/magnetic_disturbance.hpp | 8 +++--- .../solar_radiation_pressure_disturbance.cpp | 11 ++++---- .../solar_radiation_pressure_disturbance.hpp | 9 +++--- src/dynamics/dynamics.cpp | 6 ++-- src/dynamics/dynamics.hpp | 6 ++-- src/environment/global/clock_generator.cpp | 2 +- src/environment/global/clock_generator.hpp | 2 +- src/environment/global/global_environment.hpp | 10 +++---- src/environment/global/gnss_satellites.cpp | 4 +-- src/environment/global/gnss_satellites.hpp | 4 +-- .../global/initialize_global_environment.cpp | 8 +++--- .../global/initialize_global_environment.hpp | 6 ++-- src/environment/global/simulation_time.cpp | 28 +++++++++---------- src/environment/global/simulation_time.hpp | 18 ++++++------ src/environment/local/local_environment.cpp | 2 +- src/environment/local/local_environment.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 2 +- 28 files changed, 96 insertions(+), 94 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index c4535cb5d..d05b8d2de 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -11,7 +11,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime) + const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) : ComponentBase(prescaler, clock_gen), id_(id), ch_max_(ch_max), @@ -29,7 +29,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, - const SimTime* simtime) + const SimulationTime* simtime) : ComponentBase(prescaler, clock_gen, power_port), id_(id), ch_max_(ch_max), diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 688932b50..1fd57f687 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -61,7 +61,7 @@ class GNSSReceiver : public ComponentBase, public ILoggable { */ GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime); + const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); /** * @fn GNSSReceiver * @brief Constructor with power port @@ -81,7 +81,7 @@ class GNSSReceiver : public ComponentBase, public ILoggable { */ GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimTime* simtime); + const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); // Override functions for ComponentBase /** @@ -164,7 +164,7 @@ class GNSSReceiver : public ComponentBase, public ILoggable { // References const Dynamics* dynamics_; //!< Dynamics of spacecraft const GnssSatellites* gnss_satellites_; //!< Information of GNSS satellites - const SimTime* simtime_; //!< Simulation time + const SimulationTime* simtime_; //!< Simulation time // Internal Functions /** diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index ca9ba6672..a3c15a625 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -50,7 +50,7 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli } GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimTime* simtime) { + const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); GNSSReceiver gnss_r(gr_param.prescaler, clock_gen, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, @@ -59,7 +59,7 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri } GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimTime* simtime) { + const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); // PowerPort diff --git a/src/components/real/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp index 0a13347ef..71c010a46 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -19,7 +19,7 @@ * @param [in] simtime: Simulation time information */ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimTime* simtime); + const GnssSatellites* gnss_satellites, const SimulationTime* simtime); /** * @fn InitGNSSReceiver * @brief Initialize functions for GNSS Receiver with power port @@ -32,6 +32,6 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri * @param [in] simtime: Simulation time information */ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimTime* simtime); + const GnssSatellites* gnss_satellites, const SimulationTime* simtime); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index fe0967015..9558b27c4 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -50,7 +50,7 @@ std::string PCU_InitialStudy::GetLogValue() const { void PCU_InitialStudy::MainRoutine(int time_count) { double time_query = compo_step_time_ * time_count; - power_consumption_ = CalcPowerConsumption(time_query); // Should use SimTime? time_count may over flow since it is int type, + power_consumption_ = CalcPowerConsumption(time_query); // Should use SimulationTime? time_count may over flow since it is int type, UpdateChargeCurrentAndBusVoltage(); for (auto sap : saps_) { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 58dbe7a84..6a69b3cb0 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -31,7 +31,7 @@ Disturbances::~Disturbances() { } } -void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimTime* sim_time) { +void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* sim_time) { // Update disturbances that depend on the attitude (and the position) if (sim_time->GetAttitudePropagateFlag()) { InitializeForceAndTorque(); @@ -70,7 +70,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const InitGravityGradient(initialize_file_name_, global_environment->GetCelestialInformation().GetCenterBodyGravityConstant_m3_s2())); disturbances_list_.push_back(gg_dist); - SolarRadiation* srp_dist = new SolarRadiation( + SolarRadiationPressureDisturbance* srp_dist = new SolarRadiationPressureDisturbance( InitSolarRadiationPressureDisturbance(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(srp_dist); @@ -82,7 +82,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const AirDrag* air_dist = new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(air_dist); - MagDisturbance* mag_dist = new MagDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetRMMParams())); + MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetRMMParams())); disturbances_list_.push_back(mag_dist); GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index d4cbca07b..06cd66741 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -43,7 +43,7 @@ class Disturbances { * @param [in] dynamics: Dynamics information * @param [in] sim_time: Simulation time */ - void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimTime* sim_time); + void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* sim_time); /** * @fn LogSetup * @brief log setup for all disturbances diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 21a43650a..98a560bff 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -27,15 +27,15 @@ AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector& surfaces, - const Vector<3>& center_of_gravity_b_m) { +SolarRadiationPressureDisturbance InitSolarRadiationPressureDisturbance(const std::string initialize_file_path, const std::vector& surfaces, + const Vector<3>& center_of_gravity_b_m) { auto conf = IniAccess(initialize_file_path); const char* section = "SOLAR_RADIATION_PRESSURE_DISTURBANCE"; const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); const bool is_log_enable = conf.ReadEnable(section, LOG_LABEL); - SolarRadiation srp_disturbance(surfaces, center_of_gravity_b_m, is_calc_enable); + SolarRadiationPressureDisturbance srp_disturbance(surfaces, center_of_gravity_b_m, is_calc_enable); srp_disturbance.IsLogEnabled = is_log_enable; return srp_disturbance; @@ -63,12 +63,12 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons return gg_disturbance; } -MagDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params) { +MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params) { auto conf = IniAccess(initialize_file_path); const char* section = "MAGNETIC_DISTURBANCE"; const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); - MagDisturbance mag_disturbance(rmm_params, is_calc_enable); + MagneticDisturbance mag_disturbance(rmm_params, is_calc_enable); mag_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return mag_disturbance; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index 0ecd38ea6..7692d42cb 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -24,13 +24,13 @@ AirDrag InitAirDrag(const std::string initialize_file_path, const std::vector& surfaces, - const Vector<3>& center_of_gravity_b_m); +SolarRadiationPressureDisturbance InitSolarRadiationPressureDisturbance(const std::string initialize_file_path, const std::vector& surfaces, + const Vector<3>& center_of_gravity_b_m); /** * @fn InitGravityGradient @@ -49,11 +49,11 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons /** * @fn InitMagneticDisturbance - * @brief Initialize MagDisturbance class with earth gravitational constant + * @brief Initialize MagneticDisturbance class with earth gravitational constant * @param [in] initialize_file_path: Initialize file path * @param [in] rmm_params: RMM parameters */ -MagDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params); +MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params); /** * @fn InitGeoPotential diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 910597e94..485b59f4a 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -12,24 +12,24 @@ #include "../library/randomization/normal_randomization.hpp" #include "../library/randomization/random_walk.hpp" -MagDisturbance::MagDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) +MagneticDisturbance::MagneticDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); } -Vector<3> MagDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { +Vector<3> MagneticDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { CalcRMM(); torque_b_Nm_ = kMagUnit_ * outer_product(rmm_b_Am2_, magnetic_field_b_nT); return torque_b_Nm_; } -void MagDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { +void MagneticDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); CalcTorque_b_Nm(local_environment.GetGeomagneticField().GetGeomagneticFieldneticField_b_nT()); } -void MagDisturbance::CalcRMM() { +void MagneticDisturbance::CalcRMM() { static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRMMRWDev()); static libra::Vector<3> random_walk_limit(rmm_params_.GetRMMRWLimit()); static RandomWalk<3> random_walk(0.1, random_walk_std_dev, random_walk_limit); // [FIXME] step width is constant @@ -42,7 +42,7 @@ void MagDisturbance::CalcRMM() { ++random_walk; // Update random walk } -std::string MagDisturbance::GetLogHeader() const { +std::string MagneticDisturbance::GetLogHeader() const { std::string str_tmp = ""; str_tmp += WriteVector("spacecraft_magnetic_moment", "b", "Am2", 3); @@ -51,7 +51,7 @@ std::string MagDisturbance::GetLogHeader() const { return str_tmp; } -std::string MagDisturbance::GetLogValue() const { +std::string MagneticDisturbance::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(rmm_b_Am2_); diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 2efd182e0..e623a948c 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -14,18 +14,18 @@ #include "simple_disturbance.hpp" /** - * @class MagDisturbance + * @class MagneticDisturbance * @brief Class to calculate the magnetic disturbance torque */ -class MagDisturbance : public SimpleDisturbance { +class MagneticDisturbance : public SimpleDisturbance { public: /** - * @fn MagDisturbance + * @fn MagneticDisturbance * @brief Constructor * @param [in] rmm_parameters: RMM parameters of the spacecraft * @param [in] is_calculation_enabled: Calculation flag */ - MagDisturbance(const RMMParams& rmm_parameters, const bool is_calculation_enabled = true); + MagneticDisturbance(const RMMParams& rmm_parameters, const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index de2c1c137..9d9cd0ca2 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,17 +9,18 @@ #include "../library/logger/log_utility.hpp" -SolarRadiation::SolarRadiation(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) +SolarRadiationPressureDisturbance::SolarRadiationPressureDisturbance(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, + const bool is_calculation_enabled) : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) {} -void SolarRadiation::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { +void SolarRadiationPressureDisturbance::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { UNUSED(dynamics); libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().GetPressure_Nm2()); } -void SolarRadiation::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { +void SolarRadiationPressureDisturbance::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { UNUSED(input_direction_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface @@ -32,7 +33,7 @@ void SolarRadiation::CalcCoefficients(const libra::Vector<3>& input_direction_b, } } -std::string SolarRadiation::GetLogHeader() const { +std::string SolarRadiationPressureDisturbance::GetLogHeader() const { std::string str_tmp = ""; str_tmp += WriteVector("srp_torque", "b", "Nm", 3); @@ -41,7 +42,7 @@ std::string SolarRadiation::GetLogHeader() const { return str_tmp; } -std::string SolarRadiation::GetLogValue() const { +std::string SolarRadiationPressureDisturbance::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(torque_b_Nm_); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 28f508999..9f5e65427 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -13,19 +13,20 @@ #include "surface_force.hpp" /** - * @class SolarRadiation + * @class SolarRadiationPressureDisturbance * @brief Class to calculate the solar radiation pressure disturbance force and torque */ -class SolarRadiation : public SurfaceForce { +class SolarRadiationPressureDisturbance : public SurfaceForce { public: /** - * @fn SolarRadiation + * @fn SolarRadiationPressureDisturbance * @brief Constructor * @param [in] surfaces: Surface information of the spacecraft * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] * @param [in] is_calculation_enabled: Calculation flag */ - SolarRadiation(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); + SolarRadiationPressureDisturbance(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, + const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index c4d94f4ae..640956a75 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -9,7 +9,7 @@ using namespace std; -Dynamics::Dynamics(SimulationConfig* sim_config, const SimTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, +Dynamics::Dynamics(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, Structure* structure, RelativeInformation* rel_info) { Initialize(sim_config, sim_time, local_celes_info, sat_id, structure, rel_info); } @@ -20,7 +20,7 @@ Dynamics::~Dynamics() { delete temperature_; } -void Dynamics::Initialize(SimulationConfig* sim_config, const SimTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, +void Dynamics::Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, Structure* structure, RelativeInformation* rel_info) { structure_ = structure; @@ -35,7 +35,7 @@ void Dynamics::Initialize(SimulationConfig* sim_config, const SimTime* sim_time, orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); } -void Dynamics::Update(const SimTime* sim_time, const LocalCelestialInformation* local_celes_info) { +void Dynamics::Update(const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info) { // Attitude propagation if (sim_time->GetAttitudePropagateFlag()) { attitude_->Propagate(sim_time->GetElapsedTime_s()); diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index a8be22e9b..d9b07d8cc 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -40,7 +40,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] rel_info: Relative information */ - Dynamics(SimulationConfig* sim_config, const SimTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, + Dynamics(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); /** * @fn ~Dynamics @@ -58,7 +58,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] rel_info: Relative information */ - void Initialize(SimulationConfig* sim_config, const SimTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, + void Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); /** @@ -67,7 +67,7 @@ class Dynamics { * @param [in] sim_time: Simulation time * @param [in] local_celes_info: Local celestial information */ - void Update(const SimTime* sim_time, const LocalCelestialInformation* local_celes_info); + void Update(const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info); /** * @fn LogSetup * @brief Log setup for dynamics calculation diff --git a/src/environment/global/clock_generator.cpp b/src/environment/global/clock_generator.cpp index edb3d4884..e5189a924 100644 --- a/src/environment/global/clock_generator.cpp +++ b/src/environment/global/clock_generator.cpp @@ -33,7 +33,7 @@ void ClockGenerator::TickToComponents() { timer_count_++; // TODO: Consider if "timer_count" is necessary } -void ClockGenerator::UpdateComponents(const SimTime* sim_time) { +void ClockGenerator::UpdateComponents(const SimulationTime* sim_time) { if (sim_time->GetCompoUpdateFlag()) { TickToComponents(); } diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 008e7f8b7..612bb9220 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -45,7 +45,7 @@ class ClockGenerator { * @brief Execute TickToComponents when component update timing * @param [in] sim_time: Simulation time */ - void UpdateComponents(const SimTime* sim_time); + void UpdateComponents(const SimulationTime* sim_time); /** * @fn ClearTimerCount * @brief Clear time count diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 5e5cea05e..1a4170bbd 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -49,16 +49,16 @@ class GlobalEnvironment { void LogSetup(Logger& logger); /** * @fn Reset - * @brief Reset clock of SimTime + * @brief Reset clock of SimulationTime */ void Reset(void); // Getter /** - * @fn GetSimTime - * @brief Return SimTime + * @fn GetSimulationTime + * @brief Return SimulationTime */ - inline const SimTime& GetSimulationTime() const { return *simulation_time_; } + inline const SimulationTime& GetSimulationTime() const { return *simulation_time_; } /** * @fn GetCelestialInformation * @brief Return CelestialInformation @@ -76,7 +76,7 @@ class GlobalEnvironment { inline const GnssSatellites& GetGnssSatellites() const { return *gnss_satellites_; } private: - SimTime* simulation_time_; //!< Simulation time + SimulationTime* simulation_time_; //!< Simulation time CelestialInformation* celestial_information_; //!< Celestial bodies information HipparcosCatalogue* hipparcos_catalogue_; //!< Hipparcos catalogue GnssSatellites* gnss_satellites_; //!< GNSS satellites diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index f02d0ff3f..d8ac30a60 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -858,7 +858,7 @@ void GnssSatellites::Init(vector>& true_position_file, int true_p return; } -void GnssSatellites::SetUp(const SimTime* sim_time) { +void GnssSatellites::SetUp(const SimulationTime* sim_time) { if (!IsCalcEnabled()) return; tm* start_tm = initilized_tm(); @@ -879,7 +879,7 @@ void GnssSatellites::SetUp(const SimTime* sim_time) { return; } -void GnssSatellites::Update(const SimTime* sim_time) { +void GnssSatellites::Update(const SimulationTime* sim_time) { if (!IsCalcEnabled()) return; double elapsed_sec = sim_time->GetElapsedTime_s(); diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 2fd323e8c..842e1bce0 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -350,13 +350,13 @@ class GnssSatellites : public ILoggable { * @brief Setup both true and estimated GNSS satellite information * @param [in] sim_time: Simulation time information */ - void SetUp(const SimTime* sim_time); + void SetUp(const SimulationTime* sim_time); /** * @fn Update * @brief Update both true and estimated GNSS satellite information * @param [in] sim_time: Simulation time information */ - void Update(const SimTime* sim_time); + void Update(const SimulationTime* sim_time); /** * @fn GetIndexFromID diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index c38a947de..e7db29cc0 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -13,7 +13,7 @@ #define CALC_LABEL "calculation" #define LOG_LABEL "logging" -SimTime* InitSimulationTime(std::string file_name) { +SimulationTime* InitSimulationTime(std::string file_name) { IniAccess ini_file(file_name); const char* section = "TIME"; @@ -38,9 +38,9 @@ SimTime* InitSimulationTime(std::string file_name) { double sim_speed = ini_file.ReadDouble(section, "simulation_speed_setting"); - SimTime* simTime = new SimTime(end_sec, step_sec, attitude_update_interval_sec, attitude_rk_step_sec, orbit_update_interval_sec, orbit_rk_step_sec, - thermal_update_interval_sec, thermal_rk_step_sec, compo_propagate_step_sec, log_output_interval_sec, - start_ymdhms.c_str(), sim_speed); + SimulationTime* simTime = new SimulationTime(end_sec, step_sec, attitude_update_interval_sec, attitude_rk_step_sec, orbit_update_interval_sec, + orbit_rk_step_sec, thermal_update_interval_sec, thermal_rk_step_sec, compo_propagate_step_sec, + log_output_interval_sec, start_ymdhms.c_str(), sim_speed); return simTime; } diff --git a/src/environment/global/initialize_global_environment.hpp b/src/environment/global/initialize_global_environment.hpp index 657a081ea..c68ba9c9e 100644 --- a/src/environment/global/initialize_global_environment.hpp +++ b/src/environment/global/initialize_global_environment.hpp @@ -11,11 +11,11 @@ #include /** - *@fn InitSimTime - *@brief Initialize function for SimTime class + *@fn InitSimulationTime + *@brief Initialize function for SimulationTime class *@param [in] file_name: Path to the initialize function */ -SimTime* InitSimulationTime(std::string file_name); +SimulationTime* InitSimulationTime(std::string file_name); /** *@fn InitHipCatalogue diff --git a/src/environment/global/simulation_time.cpp b/src/environment/global/simulation_time.cpp index 75f224fed..68a043974 100644 --- a/src/environment/global/simulation_time.cpp +++ b/src/environment/global/simulation_time.cpp @@ -17,10 +17,10 @@ using namespace std; -SimTime::SimTime(const double end_sec, const double step_sec, const double attitude_update_interval_sec, const double attitude_rk_step_sec, - const double orbit_update_interval_sec, const double orbit_rk_step_sec, const double thermal_update_interval_sec, - const double thermal_rk_step_sec, const double compo_propagate_step_sec, const double log_output_interval_sec, - const char* start_ymdhms, const double sim_speed) { +SimulationTime::SimulationTime(const double end_sec, const double step_sec, const double attitude_update_interval_sec, + const double attitude_rk_step_sec, const double orbit_update_interval_sec, const double orbit_rk_step_sec, + const double thermal_update_interval_sec, const double thermal_rk_step_sec, const double compo_propagate_step_sec, + const double log_output_interval_sec, const char* start_ymdhms, const double sim_speed) { end_sec_ = end_sec; step_sec_ = step_sec; attitude_update_interval_sec_ = attitude_update_interval_sec; @@ -48,9 +48,9 @@ SimTime::SimTime(const double end_sec, const double step_sec, const double attit SetParameters(); } -SimTime::~SimTime() {} +SimulationTime::~SimulationTime() {} -void SimTime::AssertTimeStepParams() { +void SimulationTime::AssertTimeStepParams() { // Runge-Kutta time step must be smaller than its update interval assert(attitude_rk_step_sec_ <= attitude_update_interval_sec_); assert(orbit_rk_step_sec_ <= orbit_update_interval_sec_); @@ -64,7 +64,7 @@ void SimTime::AssertTimeStepParams() { assert(step_sec_ <= log_output_interval_sec_); } -void SimTime::SetParameters(void) { +void SimulationTime::SetParameters(void) { elapsed_time_sec_ = 0.0; attitude_update_counter_ = 1; attitude_update_flag_ = false; @@ -79,7 +79,7 @@ void SimTime::SetParameters(void) { state_.log_output = true; } -void SimTime::UpdateTime(void) { +void SimulationTime::UpdateTime(void) { InitializeState(); elapsed_time_sec_ += step_sec_; if (simulation_speed_ > 0) { @@ -166,9 +166,9 @@ void SimTime::UpdateTime(void) { state_.running = true; } -void SimTime::ResetClock(void) { clock_start_time_millisec_ = chrono::system_clock::now(); } +void SimulationTime::ResetClock(void) { clock_start_time_millisec_ = chrono::system_clock::now(); } -void SimTime::PrintStartDateTime(void) const { +void SimulationTime::PrintStartDateTime(void) const { int sec_int = int(start_sec_ + 0.5); stringstream s, m, h; if (sec_int < 10) { @@ -190,7 +190,7 @@ void SimTime::PrintStartDateTime(void) const { cout << " " << start_year_ << "/" << start_month_ << "/" << start_day_ << " " << h.str() << ":" << m.str() << ":" << s.str() << "\n"; } -string SimTime::GetLogHeader() const { +string SimulationTime::GetLogHeader() const { string str_tmp = ""; str_tmp += WriteScalar("elapsed_time", "s"); @@ -199,7 +199,7 @@ string SimTime::GetLogHeader() const { return str_tmp; } -string SimTime::GetLogValue() const { +string SimulationTime::GetLogValue() const { string str_tmp = ""; str_tmp += WriteScalar(elapsed_time_sec_); @@ -213,7 +213,7 @@ string SimTime::GetLogValue() const { return str_tmp; } -void SimTime::InitializeState() { +void SimulationTime::InitializeState() { state_.disp_output = false; state_.finish = false; state_.log_output = false; @@ -221,7 +221,7 @@ void SimTime::InitializeState() { } // wrapper function of invjday @ sgp4ext for interface adjustment -void SimTime::ConvJDtoCalndarDay(const double JD) { +void SimulationTime::ConvJDtoCalndarDay(const double JD) { int year, mon, day, hr, minute; double sec; invjday(JD, year, mon, day, hr, minute, sec); diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index bee1a1da5..77a307207 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -44,13 +44,13 @@ struct UTC { }; /** - *@class SimTime + *@class SimulationTime *@brief Class to manage simulation time related information */ -class SimTime : public ILoggable { +class SimulationTime : public ILoggable { public: /** - *@fn SimTime + *@fn SimulationTime *@brief Constructor *@param [in] end_sec: Simulation duration [sec] *@param [in] step_sec: Simulation step [sec] @@ -65,15 +65,15 @@ class SimTime : public ILoggable { *@param [in] start_ymdhms: Simulation start time in UTC [YYYYMMDD hh:mm:ss] *@param [in] sim_speed: Simulation speed setting */ - SimTime(const double end_sec, const double step_sec, const double attitude_update_interval_sec, const double attitude_rk_step_sec, - const double orbit_update_interval_sec, const double orbit_rk_step_sec, const double thermal_update_interval_sec, - const double thermal_rk_step_sec, const double compo_propagate_step_sec, const double log_output_interval_sec, const char* start_ymdhms, - const double sim_speed); + SimulationTime(const double end_sec, const double step_sec, const double attitude_update_interval_sec, const double attitude_rk_step_sec, + const double orbit_update_interval_sec, const double orbit_rk_step_sec, const double thermal_update_interval_sec, + const double thermal_rk_step_sec, const double compo_propagate_step_sec, const double log_output_interval_sec, + const char* start_ymdhms, const double sim_speed); /** - *@fn ~SimTime + *@fn ~SimulationTime *@brief Destructor */ - virtual ~SimTime(); + virtual ~SimulationTime(); /** *@fn SetParameters diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 159e7ecc3..a6c8259e5 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -48,7 +48,7 @@ void LocalEnvironment::Initialize(const SimulationConfig* simulation_configurati celestial_information_->IsLogEnabled = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); } -void LocalEnvironment::Update(const Dynamics* dynamics, const SimTime* simulation_time) { +void LocalEnvironment::Update(const Dynamics* dynamics, const SimulationTime* simulation_time) { auto& orbit = dynamics->GetOrbit(); auto& attitude = dynamics->GetAttitude(); diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 240334e1d..6e3afcb23 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -40,7 +40,7 @@ class LocalEnvironment { * @param [in] dynamics: Dynamics information of the satellite * @param [in] simulation_time: Simulation time */ - void Update(const Dynamics* dynamics, const SimTime* simulation_time); + void Update(const Dynamics* dynamics, const SimulationTime* simulation_time); /** * @fn LogSetup diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index ece00aecf..acf0fc873 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -60,7 +60,7 @@ void Spacecraft::LogSetup(Logger& logger) { components_->LogSetup(logger); } -void Spacecraft::Update(const SimTime* sim_time) { +void Spacecraft::Update(const SimulationTime* sim_time) { dynamics_->ClearForceTorque(); // Update local environment and disturbance diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 3d9b66cf3..0252ca8d6 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -58,7 +58,7 @@ class Spacecraft { * @fn Update * @brief Update all states related with the spacecraft */ - virtual void Update(const SimTime* sim_time); + virtual void Update(const SimulationTime* sim_time); /** * @fn Clear From 8326fecdb6ca19af497070e41581619719eaefb3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:32:58 +0100 Subject: [PATCH 0562/1086] Fix private function name --- src/disturbances/air_drag.cpp | 14 +++++++------- src/disturbances/air_drag.hpp | 12 ++++++------ 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 2612d1522..adfca7f9f 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -30,7 +30,7 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3) { double velocity_norm_m_s = norm(velocity_b_m_s); - CalCnCt(velocity_b_m_s); + CalcCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); normal_coefficients_[i] = k * cn_[i]; @@ -38,21 +38,21 @@ void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const dou } } -double AirDrag::CalcFuncPi(const double s) { +double AirDrag::CalcFunctionPi(const double s) { double x; double erfs = erf(s); // ERF function is defined in math standard library x = s * exp(-s * s) + sqrt(libra::pi) * (s * s + 0.5) * (1.0 + erfs); return x; } -double AirDrag::CalcFuncChi(const double s) { +double AirDrag::CalcFunctionChi(const double s) { double x; double erfs = erf(s); x = exp(-s * s) + sqrt(libra::pi) * s * (1.0 + erfs); return x; } -void AirDrag::CalCnCt(const Vector<3>& velocity_b_m_s) { +void AirDrag::CalcCnCt(const Vector<3>& velocity_b_m_s) { double velocity_norm_m_s = norm(velocity_b_m_s); // Re-emitting speed @@ -63,9 +63,9 @@ void AirDrag::CalCnCt(const Vector<3>& velocity_b_m_s) { double speed_n = speed * cos_theta_[i]; double speed_t = speed * sin_theta_[i]; double diffuse = 1.0 - surfaces_[i].GetAirSpecularity(); - cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * CalcFuncPi(speed_n) / (speed * speed) + - diffuse / 2.0 * CalcFuncChi(speed_n) / (speed * speed) * sqrt(wall_temperature_K_ / molecular_temperature_K_); - ct_[i] = diffuse * speed_t * CalcFuncChi(speed_n) / (sqrt(libra::pi) * speed * speed); + cn_[i] = (2.0 - diffuse) / sqrt(libra::pi) * CalcFunctionPi(speed_n) / (speed * speed) + + diffuse / 2.0 * CalcFunctionChi(speed_n) / (speed * speed) * sqrt(wall_temperature_K_ / molecular_temperature_K_); + ct_[i] = diffuse * speed_t * CalcFunctionChi(speed_n) / (sqrt(libra::pi) * speed * speed); } } diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index 261a1aa36..c453a62f3 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -70,23 +70,23 @@ class AirDrag : public SurfaceForce { // internal function for calculation /** - * @fn CalCnCt + * @fn CalcCnCt * @brief Calculate the Cn and Ct * @param [in] velocity_b_m_s: Spacecraft's velocity vector in the body frame [m/s] */ - void CalCnCt(const libra::Vector<3>& velocity_b_m_s); + void CalcCnCt(const libra::Vector<3>& velocity_b_m_s); /** - * @fn CalcFuncPi + * @fn CalcFunctionPi * @brief Calculate The Pi function in the algorithm * @param [in] s: Independent variable of the Pi function */ - double CalcFuncPi(const double s); + double CalcFunctionPi(const double s); /** - * @fn CalcFuncChi + * @fn CalcFunctionChi * @brief Calculate The Chi function in the algorithm * @param [in] s: Independent variable of the Chi function */ - double CalcFuncChi(const double s); + double CalcFunctionChi(const double s); }; #endif // S2E_DISTURBANCES_AIR_DRAG_HPP_ From b74993f76bb93ac884c1eba17a0db438970fd974 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:41:18 +0100 Subject: [PATCH 0563/1086] Revert unnecessary change --- src/components/real/aocs/magnetometer.hpp | 4 ++-- src/components/real/aocs/magnetorquer.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 09ee06eb5..eef494fd9 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -72,10 +72,10 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg virtual std::string GetLogValue() const; /** - * @fn GetGeomagneticFieldC + * @fn GetMagC * @brief Return observed magnetic field on the component frame */ - inline const libra::Vector& GetGeomagneticFieldC(void) const { return mag_c_; } + inline const libra::Vector& GetMagC(void) const { return mag_c_; } protected: libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index d4ae0d1b4..ef66997a4 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -93,10 +93,10 @@ class MagTorquer : public ComponentBase, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetGeomagneticFieldMoment_b + * @fn GetMagMoment_b * @brief Return output magnetic moment in the body fixed frame [Am2] */ - inline const libra::Vector& GetGeomagneticFieldMoment_b(void) const { return mag_moment_b_; }; + inline const libra::Vector& GetMagMoment_b(void) const { return mag_moment_b_; }; /** * @fn GetTorque_b * @brief Return output torque in the body fixed frame [Nm] From 51ad4f0e42e88f0cfcc8502e8eda3c21b178dee7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:44:26 +0100 Subject: [PATCH 0564/1086] Fix public function name --- src/disturbances/solar_radiation_pressure_disturbance.cpp | 2 +- .../local/solar_radiation_pressure_environment.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 9d9cd0ca2..808ddeb5c 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -17,7 +17,7 @@ void SolarRadiationPressureDisturbance::Update(const LocalEnvironment& local_env UNUSED(dynamics); libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); - CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().GetPressure_Nm2()); + CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().GetPressure_N_m2()); } void SolarRadiationPressureDisturbance::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { diff --git a/src/environment/local/solar_radiation_pressure_environment.hpp b/src/environment/local/solar_radiation_pressure_environment.hpp index 3a3576491..ecb3c5c29 100644 --- a/src/environment/local/solar_radiation_pressure_environment.hpp +++ b/src/environment/local/solar_radiation_pressure_environment.hpp @@ -37,10 +37,10 @@ class SolarRadiationPressureEnvironment : public ILoggable { // Getter /** - * @fn GetPressure_Nm2 + * @fn GetPressure_N_m2 * @brief Calculate and return solar radiation pressure that takes into account eclipse [N/m^2] */ - inline double GetPressure_Nm2() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } + inline double GetPressure_N_m2() const { return solar_radiation_pressure_N_m2_ * shadow_coefficient_; } /** * @fn GetPowerDensity_W_m2 * @brief Calculate and return solar power per unit area considering eclipse [W/m^2] From e57aabc4b13a54523d929b6d755a7cc779a5c818 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:50:33 +0100 Subject: [PATCH 0565/1086] Fix format --- src/components/real/aocs/initialize_sun_sensor.cpp | 4 ++-- src/dynamics/dynamics.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index ca95703e5..ae809c1c5 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -43,8 +43,8 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n return ss; } -SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info) { +SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 640956a75..a099a865c 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -20,8 +20,8 @@ Dynamics::~Dynamics() { delete temperature_; } -void Dynamics::Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, - Structure* structure, RelativeInformation* rel_info) { +void Dynamics::Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, + const int sat_id, Structure* structure, RelativeInformation* rel_info) { structure_ = structure; // Initialize From e12246068593af3658d1300d13e4e8d325beebf3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 15:58:00 +0100 Subject: [PATCH 0566/1086] clean include files --- src/dynamics/dynamics.cpp | 14 +++++------ src/dynamics/dynamics.hpp | 52 ++++++++++++++++++--------------------- 2 files changed, 30 insertions(+), 36 deletions(-) diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index a099a865c..d8c53db8e 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -7,8 +7,6 @@ #include "../simulation/multiple_spacecraft/relative_information.hpp" -using namespace std; - Dynamics::Dynamics(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, Structure* structure, RelativeInformation* rel_info) { Initialize(sim_config, sim_time, local_celes_info, sat_id, structure, rel_info); @@ -58,7 +56,7 @@ void Dynamics::Update(const SimulationTime* sim_time, const LocalCelestialInform } void Dynamics::ClearForceTorque(void) { - Vector<3> zero(0.0); + libra::Vector<3> zero(0.0); attitude_->SetTorque_b(zero); orbit_->SetAcceleration_i(zero); } @@ -68,14 +66,14 @@ void Dynamics::LogSetup(Logger& logger) { logger.AddLoggable(orbit_); } -void Dynamics::AddTorque_b(Vector<3> torque_b) { attitude_->AddTorque_b(torque_b); } +void Dynamics::AddTorque_b(libra::Vector<3> torque_b) { attitude_->AddTorque_b(torque_b); } -void Dynamics::AddForce_b(Vector<3> force_b) { +void Dynamics::AddForce_b(libra::Vector<3> force_b) { orbit_->AddForce_b(force_b, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); } -void Dynamics::AddAcceleration_i(Vector<3> acceleration_i) { orbit_->AddAcceleration_i(acceleration_i); } +void Dynamics::AddAcceleration_i(libra::Vector<3> acceleration_i) { orbit_->AddAcceleration_i(acceleration_i); } -Vector<3> Dynamics::GetPosition_i() const { return orbit_->GetSatPosition_i(); } +libra::Vector<3> Dynamics::GetPosition_i() const { return orbit_->GetSatPosition_i(); } -Quaternion Dynamics::GetQuaternion_i2b() const { return attitude_->GetQuaternion_i2b(); } +libra::Quaternion Dynamics::GetQuaternion_i2b() const { return attitude_->GetQuaternion_i2b(); } diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index d9b07d8cc..b77160845 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -7,20 +7,15 @@ #include -#include "../library/math/vector.hpp" -using libra::Vector; - -#include -#include -#include -#include - #include "../environment/global/simulation_time.hpp" #include "../environment/local/local_celestial_information.hpp" +#include "../library/math/vector.hpp" #include "../simulation/simulation_configuration.hpp" #include "../simulation/spacecraft/structure/structure.hpp" -#include "./orbit/orbit.hpp" -#include "./thermal/temperature.hpp" +#include "dynamics/attitude/initialize_attitude.hpp" +#include "dynamics/orbit/initialize_orbit.hpp" +#include "dynamics/thermal/initialize_node.hpp" +#include "dynamics/thermal/initialize_temperature.hpp" class RelativeInformation; @@ -48,19 +43,6 @@ class Dynamics { */ virtual ~Dynamics(); - /** - * @fn Initialize - * @brief Initialize function - * @param [in] sim_config: Simulation config - * @param [in] sim_time: Simulation time - * @param [in] local_celes_info: Local celestial information - * @param [in] sat_id: Spacecraft ID of the spacecraft - * @param [in] structure: Structure of the spacecraft - * @param [in] rel_info: Relative information - */ - void Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, - Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); - /** * @fn Update * @brief Update states of all dynamics calculations @@ -68,6 +50,7 @@ class Dynamics { * @param [in] local_celes_info: Local celestial information */ void Update(const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info); + /** * @fn LogSetup * @brief Log setup for dynamics calculation @@ -79,19 +62,19 @@ class Dynamics { * @brief Add input torque for the attitude dynamics propagation * @param [in] torue_b: Torque in the body fixed frame [Nm] */ - void AddTorque_b(Vector<3> torque_b); + void AddTorque_b(libra::Vector<3> torque_b); /** * @fn AddForce_b * @brief Add input force for the orbit dynamics propagation * @param [in] force_b: Force in the body fixed frame [N] */ - void AddForce_b(Vector<3> force_b); + void AddForce_b(libra::Vector<3> force_b); /** * @fn AddAcceleratione_b * @brief Add input acceleration for the orbit dynamics propagation * @param [in] acceleration_b: Force in the body fixed frame [N] */ - void AddAcceleration_i(Vector<3> acceleration_i); + void AddAcceleration_i(libra::Vector<3> acceleration_i); /** * @fn ClearForceTorque * @brief Clear force, acceleration, and torque for the dynamics propagation @@ -123,19 +106,32 @@ class Dynamics { * @fn GetPosition_i * @brief Return spacecraft position in the inertial frame [m] */ - virtual Vector<3> GetPosition_i() const; + virtual libra::Vector<3> GetPosition_i() const; /** * @fn GetQuaternion_i2b * @brief Return spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - virtual Quaternion GetQuaternion_i2b() const; + virtual libra::Quaternion GetQuaternion_i2b() const; private: Attitude* attitude_; //!< Attitude dynamics Orbit* orbit_; //!< Orbit dynamics Temperature* temperature_; //!< Thermal dynamics const Structure* structure_; //!< Structure information + + /** + * @fn Initialize + * @brief Initialize function + * @param [in] sim_config: Simulation config + * @param [in] sim_time: Simulation time + * @param [in] local_celes_info: Local celestial information + * @param [in] sat_id: Spacecraft ID of the spacecraft + * @param [in] structure: Structure of the spacecraft + * @param [in] rel_info: Relative information + */ + void Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, + Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); }; #endif // S2E_DYNAMICS_DYNAMICS_HPP_ From 2161a67ae593b4ca8688758f610826f2342d5f27 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:02:20 +0100 Subject: [PATCH 0567/1086] Fix function argument names --- src/dynamics/dynamics.cpp | 45 +++++++++++++++++++---------------- src/dynamics/dynamics.hpp | 50 ++++++++++++++++++++------------------- 2 files changed, 50 insertions(+), 45 deletions(-) diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index d8c53db8e..634602e42 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -7,9 +7,10 @@ #include "../simulation/multiple_spacecraft/relative_information.hpp" -Dynamics::Dynamics(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, - Structure* structure, RelativeInformation* rel_info) { - Initialize(sim_config, sim_time, local_celes_info, sat_id, structure, rel_info); +Dynamics::Dynamics(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, + RelativeInformation* relative_information) { + Initialize(simulation_configuration, simulation_time, local_celestial_information, spacecraft_id, structure, relative_information); } Dynamics::~Dynamics() { @@ -18,39 +19,41 @@ Dynamics::~Dynamics() { delete temperature_; } -void Dynamics::Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, - const int sat_id, Structure* structure, RelativeInformation* rel_info) { +void Dynamics::Initialize(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, + RelativeInformation* relative_information) { structure_ = structure; // Initialize - orbit_ = InitOrbit(&(local_celes_info->GetGlobalInformation()), sim_config->sat_file_[sat_id], sim_time->GetOrbitRkStepTime_s(), - sim_time->GetCurrentTime_jd(), local_celes_info->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", rel_info); - attitude_ = InitAttitude(sim_config->sat_file_[sat_id], orbit_, local_celes_info, sim_time->GetAttitudeRkStepTime_s(), - structure->GetKinematicsParams().GetInertiaTensor(), sat_id); - temperature_ = InitTemperature(sim_config->sat_file_[sat_id], sim_time->GetThermalRkStepTime_s()); + orbit_ = InitOrbit(&(local_celestial_information->GetGlobalInformation()), simulation_configuration->sat_file_[spacecraft_id], + simulation_time->GetOrbitRkStepTime_s(), simulation_time->GetCurrentTime_jd(), + local_celestial_information->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", relative_information); + attitude_ = InitAttitude(simulation_configuration->sat_file_[spacecraft_id], orbit_, local_celestial_information, + simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor(), spacecraft_id); + temperature_ = InitTemperature(simulation_configuration->sat_file_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); // To get initial value orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); } -void Dynamics::Update(const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info) { +void Dynamics::Update(const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information) { // Attitude propagation - if (sim_time->GetAttitudePropagateFlag()) { - attitude_->Propagate(sim_time->GetElapsedTime_s()); + if (simulation_time->GetAttitudePropagateFlag()) { + attitude_->Propagate(simulation_time->GetElapsedTime_s()); } // Orbit Propagation - if (sim_time->GetOrbitPropagateFlag()) { - orbit_->Propagate(sim_time->GetElapsedTime_s(), sim_time->GetCurrentTime_jd()); + if (simulation_time->GetOrbitPropagateFlag()) { + orbit_->Propagate(simulation_time->GetElapsedTime_s(), simulation_time->GetCurrentTime_jd()); } // Attitude dependent update orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); // Thermal - if (sim_time->GetThermalPropagateFlag()) { + if (simulation_time->GetThermalPropagateFlag()) { std::string sun_str = "SUN"; char* c_sun = new char[sun_str.size() + 1]; std::char_traits::copy(c_sun, sun_str.c_str(), sun_str.size() + 1); // string -> char* - temperature_->Propagate(local_celes_info->GetPositionFromSpacecraft_b_m(c_sun), sim_time->GetElapsedTime_s()); + temperature_->Propagate(local_celestial_information->GetPositionFromSpacecraft_b_m(c_sun), simulation_time->GetElapsedTime_s()); delete[] c_sun; } } @@ -66,13 +69,13 @@ void Dynamics::LogSetup(Logger& logger) { logger.AddLoggable(orbit_); } -void Dynamics::AddTorque_b(libra::Vector<3> torque_b) { attitude_->AddTorque_b(torque_b); } +void Dynamics::AddTorque_b(libra::Vector<3> torque_b_Nm) { attitude_->AddTorque_b(torque_b_Nm); } -void Dynamics::AddForce_b(libra::Vector<3> force_b) { - orbit_->AddForce_b(force_b, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); +void Dynamics::AddForce_b(libra::Vector<3> force_b_N) { + orbit_->AddForce_b(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); } -void Dynamics::AddAcceleration_i(libra::Vector<3> acceleration_i) { orbit_->AddAcceleration_i(acceleration_i); } +void Dynamics::AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i(acceleration_i_m_s2); } libra::Vector<3> Dynamics::GetPosition_i() const { return orbit_->GetSatPosition_i(); } diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index b77160845..48036962c 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -28,15 +28,16 @@ class Dynamics { /** * @fn Dynamics * @brief Constructor - * @param [in] sim_config: Simulation config - * @param [in] sim_time: Simulation time - * @param [in] local_celes_info: Local celestial information - * @param [in] sat_id: Spacecraft ID of the spacecraft + * @param [in] simulation_configuration: Simulation config + * @param [in] simulation_time: Simulation time + * @param [in] local_celestial_information: Local celestial information + * @param [in] spacecraft_id: Spacecraft ID of the spacecraft * @param [in] structure: Structure of the spacecraft - * @param [in] rel_info: Relative information + * @param [in] relative_information: Relative information */ - Dynamics(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, - Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); + Dynamics(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, + RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** * @fn ~Dynamics * @brief Destructor @@ -46,10 +47,10 @@ class Dynamics { /** * @fn Update * @brief Update states of all dynamics calculations - * @param [in] sim_time: Simulation time - * @param [in] local_celes_info: Local celestial information + * @param [in] simulation_time: Simulation time + * @param [in] local_celestial_information: Local celestial information */ - void Update(const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info); + void Update(const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information); /** * @fn LogSetup @@ -60,21 +61,21 @@ class Dynamics { /** * @fn AddTorque_b * @brief Add input torque for the attitude dynamics propagation - * @param [in] torue_b: Torque in the body fixed frame [Nm] + * @param [in] torque_b_Nm: Torque in the body fixed frame [Nm] */ - void AddTorque_b(libra::Vector<3> torque_b); + void AddTorque_b(libra::Vector<3> torque_b_Nm); /** * @fn AddForce_b * @brief Add input force for the orbit dynamics propagation - * @param [in] force_b: Force in the body fixed frame [N] + * @param [in] force_b_N: Force in the body fixed frame [N] */ - void AddForce_b(libra::Vector<3> force_b); + void AddForce_b(libra::Vector<3> force_b_N); /** - * @fn AddAcceleratione_b + * @fn AddAcceleratione_i * @brief Add input acceleration for the orbit dynamics propagation - * @param [in] acceleration_b: Force in the body fixed frame [N] + * @param [in] acceleration_i_m_s2: Acceleration in the inertial fixed frame [N] */ - void AddAcceleration_i(libra::Vector<3> acceleration_i); + void AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2); /** * @fn ClearForceTorque * @brief Clear force, acceleration, and torque for the dynamics propagation @@ -123,15 +124,16 @@ class Dynamics { /** * @fn Initialize * @brief Initialize function - * @param [in] sim_config: Simulation config - * @param [in] sim_time: Simulation time - * @param [in] local_celes_info: Local celestial information - * @param [in] sat_id: Spacecraft ID of the spacecraft + * @param [in] simulation_configuration: Simulation config + * @param [in] simulation_time: Simulation time + * @param [in] local_celestial_information: Local celestial information + * @param [in] spacecraft_id: Spacecraft ID of the spacecraft * @param [in] structure: Structure of the spacecraft - * @param [in] rel_info: Relative information + * @param [in] relative_information: Relative information */ - void Initialize(SimulationConfig* sim_config, const SimulationTime* sim_time, const LocalCelestialInformation* local_celes_info, const int sat_id, - Structure* structure, RelativeInformation* rel_info = (RelativeInformation*)nullptr); + void Initialize(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, + RelativeInformation* relative_information = (RelativeInformation*)nullptr); }; #endif // S2E_DYNAMICS_DYNAMICS_HPP_ From ecdea90e8d2c8141c1940be18898fcdd48927769 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:05:52 +0100 Subject: [PATCH 0568/1086] Move to inline functions --- src/dynamics/dynamics.cpp | 4 ---- src/dynamics/dynamics.hpp | 4 ++-- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 634602e42..c4f3f39c9 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -76,7 +76,3 @@ void Dynamics::AddForce_b(libra::Vector<3> force_b_N) { } void Dynamics::AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i(acceleration_i_m_s2); } - -libra::Vector<3> Dynamics::GetPosition_i() const { return orbit_->GetSatPosition_i(); } - -libra::Quaternion Dynamics::GetQuaternion_i2b() const { return attitude_->GetQuaternion_i2b(); } diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 48036962c..836a3f0f4 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -107,13 +107,13 @@ class Dynamics { * @fn GetPosition_i * @brief Return spacecraft position in the inertial frame [m] */ - virtual libra::Vector<3> GetPosition_i() const; + inline libra::Vector<3> GetPosition_i() const { return orbit_->GetSatPosition_i(); } /** * @fn GetQuaternion_i2b * @brief Return spacecraft attitude quaternion from the inertial frame to the body fixed frame */ - virtual libra::Quaternion GetQuaternion_i2b() const; + inline libra::Quaternion GetQuaternion_i2b() const { return attitude_->GetQuaternion_i2b(); } private: Attitude* attitude_; //!< Attitude dynamics From 3c64e4b297b8ac40e71b91ff56b86d51d95e54b2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:07:59 +0100 Subject: [PATCH 0569/1086] Remove unnecesarry Get function --- src/components/real/aocs/gnss_receiver.cpp | 2 +- src/dynamics/dynamics.hpp | 14 +------------- 2 files changed, 2 insertions(+), 14 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index d05b8d2de..c037bae9a 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -49,7 +49,7 @@ void GNSSReceiver::MainRoutine(int count) { UNUSED(count); Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetSatPosition_i(); - Quaternion q_i2b = dynamics_->GetQuaternion_i2b(); + Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); CheckAntenna(pos_true_eci_, q_i2b); diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 836a3f0f4..e1338ee21 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -71,7 +71,7 @@ class Dynamics { */ void AddForce_b(libra::Vector<3> force_b_N); /** - * @fn AddAcceleratione_i + * @fn AddAcceleration_i * @brief Add input acceleration for the orbit dynamics propagation * @param [in] acceleration_i_m_s2: Acceleration in the inertial fixed frame [N] */ @@ -103,18 +103,6 @@ class Dynamics { */ inline Attitude& SetAttitude() const { return *attitude_; } - /** - * @fn GetPosition_i - * @brief Return spacecraft position in the inertial frame [m] - */ - inline libra::Vector<3> GetPosition_i() const { return orbit_->GetSatPosition_i(); } - - /** - * @fn GetQuaternion_i2b - * @brief Return spacecraft attitude quaternion from the inertial frame to the body fixed frame - */ - inline libra::Quaternion GetQuaternion_i2b() const { return attitude_->GetQuaternion_i2b(); } - private: Attitude* attitude_; //!< Attitude dynamics Orbit* orbit_; //!< Orbit dynamics From 1a8d1b6e8e863eb6c940519004e98aaf6e9eff95 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:11:16 +0100 Subject: [PATCH 0570/1086] Move to inline functions --- src/dynamics/dynamics.cpp | 8 -------- src/dynamics/dynamics.hpp | 9 ++++++--- 2 files changed, 6 insertions(+), 11 deletions(-) diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index c4f3f39c9..c000bafc2 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -68,11 +68,3 @@ void Dynamics::LogSetup(Logger& logger) { logger.AddLoggable(attitude_); logger.AddLoggable(orbit_); } - -void Dynamics::AddTorque_b(libra::Vector<3> torque_b_Nm) { attitude_->AddTorque_b(torque_b_Nm); } - -void Dynamics::AddForce_b(libra::Vector<3> force_b_N) { - orbit_->AddForce_b(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); -} - -void Dynamics::AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i(acceleration_i_m_s2); } diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index e1338ee21..fbf24735b 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -63,19 +63,22 @@ class Dynamics { * @brief Add input torque for the attitude dynamics propagation * @param [in] torque_b_Nm: Torque in the body fixed frame [Nm] */ - void AddTorque_b(libra::Vector<3> torque_b_Nm); + inline void AddTorque_b(libra::Vector<3> torque_b_Nm) { attitude_->AddTorque_b(torque_b_Nm); } /** * @fn AddForce_b * @brief Add input force for the orbit dynamics propagation * @param [in] force_b_N: Force in the body fixed frame [N] */ - void AddForce_b(libra::Vector<3> force_b_N); + inline void AddForce_b(libra::Vector<3> force_b_N) { + orbit_->AddForce_b(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); + } /** * @fn AddAcceleration_i * @brief Add input acceleration for the orbit dynamics propagation * @param [in] acceleration_i_m_s2: Acceleration in the inertial fixed frame [N] */ - void AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2); + inline void AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i(acceleration_i_m_s2); } + /** * @fn ClearForceTorque * @brief Clear force, acceleration, and torque for the dynamics propagation From 453c1dbe4241779c5227e32f5c2de2015bcc17f7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:13:16 +0100 Subject: [PATCH 0571/1086] Rename public functions --- src/dynamics/attitude/attitude.hpp | 4 ++-- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/dynamics.hpp | 14 +++++++------- src/dynamics/orbit/orbit.hpp | 6 +++--- src/simulation/spacecraft/spacecraft.cpp | 10 +++++----- 5 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index d1a66264b..f405ecf78 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -110,10 +110,10 @@ class Attitude : public ILoggable, public SimulationObject { */ inline void SetTorque_b(const libra::Vector<3> set) { torque_b_Nm_ = set; } /** - * @fn AddTorque_b + * @fn AddTorque_b_Nm * @brief Add torque acting on the spacecraft on the body fixed frame [Nm] */ - inline void AddTorque_b(const libra::Vector<3> set) { torque_b_Nm_ += set; } + inline void AddTorque_b_Nm(const libra::Vector<3> set) { torque_b_Nm_ += set; } /** * @fn SetAngMom_rw * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 2f86e16c3..0c8674bcd 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -160,7 +160,7 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { controlled_torque_b_Nm = libra::Vector<3>(0.0); } // Add torque with disturbances - AddTorque_b(controlled_torque_b_Nm); + AddTorque_b_Nm(controlled_torque_b_Nm); // save previous values previous_calc_time_s_ = current_time_s; prev_quaternion_i2b_ = quaternion_i2b_; diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index fbf24735b..75cf2e727 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -59,25 +59,25 @@ class Dynamics { void LogSetup(Logger& logger); /** - * @fn AddTorque_b + * @fn AddTorque_b_Nm * @brief Add input torque for the attitude dynamics propagation * @param [in] torque_b_Nm: Torque in the body fixed frame [Nm] */ - inline void AddTorque_b(libra::Vector<3> torque_b_Nm) { attitude_->AddTorque_b(torque_b_Nm); } + inline void AddTorque_b_Nm(libra::Vector<3> torque_b_Nm) { attitude_->AddTorque_b_Nm(torque_b_Nm); } /** - * @fn AddForce_b + * @fn AddForce_b_N * @brief Add input force for the orbit dynamics propagation * @param [in] force_b_N: Force in the body fixed frame [N] */ - inline void AddForce_b(libra::Vector<3> force_b_N) { - orbit_->AddForce_b(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); + inline void AddForce_b_N(libra::Vector<3> force_b_N) { + orbit_->AddForce_b_N(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); } /** - * @fn AddAcceleration_i + * @fn AddAcceleration_i_m_s2 * @brief Add input acceleration for the orbit dynamics propagation * @param [in] acceleration_i_m_s2: Acceleration in the inertial fixed frame [N] */ - inline void AddAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i(acceleration_i_m_s2); } + inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { orbit_->AddAcceleration_i_m_s2(acceleration_i_m_s2); } /** * @fn ClearForceTorque diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 03152777a..c9c033424 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -160,10 +160,10 @@ class Orbit : public ILoggable { acc_i_ += force_i; } /** - * @fn AddAcceleration_i + * @fn AddAcceleration_i_m_s2 * @brief Add acceleration in the inertial frame [m/s2] */ - inline void AddAcceleration_i(Vector<3> acceleration_i) { acc_i_ += acceleration_i; } + inline void AddAcceleration_i_m_s2(Vector<3> acceleration_i) { acc_i_ += acceleration_i; } /** * @fn AddForce_i * @brief Add force @@ -171,7 +171,7 @@ class Orbit : public ILoggable { * @param [in] q_i2b: Quaternion from the inertial frame to the body fixed frame * @param [in] spacecraft_mass: Mass of spacecraft [kg] */ - inline void AddForce_b(Vector<3> force_b, Quaternion q_i2b, double spacecraft_mass) { + inline void AddForce_b_N(Vector<3> force_b, Quaternion q_i2b, double spacecraft_mass) { auto force_i = q_i2b.frame_conv_inv(force_b); AddForce_i(force_i, spacecraft_mass); } diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index acf0fc873..297a3df6c 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -71,13 +71,13 @@ void Spacecraft::Update(const SimulationTime* sim_time) { clock_gen_.UpdateComponents(sim_time); // Add generated force and torque by disturbances - dynamics_->AddAcceleration_i(disturbances_->GetAcceleration_i_m_s2()); - dynamics_->AddTorque_b(disturbances_->GetTorque_b_Nm()); - dynamics_->AddForce_b(disturbances_->GetForce_b_N()); + dynamics_->AddAcceleration_i_m_s2(disturbances_->GetAcceleration_i_m_s2()); + dynamics_->AddTorque_b_Nm(disturbances_->GetTorque_b_Nm()); + dynamics_->AddForce_b_N(disturbances_->GetForce_b_N()); // Add generated force and torque by components - dynamics_->AddTorque_b(components_->GenerateTorque_Nm_b()); - dynamics_->AddForce_b(components_->GenerateForce_N_b()); + dynamics_->AddTorque_b_Nm(components_->GenerateTorque_Nm_b()); + dynamics_->AddForce_b_N(components_->GenerateForce_N_b()); // Propagate dynamics dynamics_->Update(sim_time, &(local_env_->GetCelestialInformation())); From 5aae154a68085098f1826cab9950b8216abd7205 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:19:52 +0100 Subject: [PATCH 0572/1086] Remove TODO --- src/dynamics/attitude/attitude.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index f405ecf78..a6257dae3 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -152,7 +152,7 @@ class Attitude : public ILoggable, public SimulationObject { protected: bool is_calc_enabled_ = true; //!< Calculation flag - double prop_step_s_; //!< Propagation step [sec] TODO: consider is it really need here + double prop_step_s_; //!< Propagation step [sec] libra::Vector<3> omega_b_rad_s_; //!< Angular velocity of spacecraft body fixed frame with respect to the inertial frame [rad/s] libra::Quaternion quaternion_i2b_; //!< Attitude quaternion from the inertial frame to the body fixed frame libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] From da88fdd78b34be91285b1e39fd6dab60be351709 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:25:15 +0100 Subject: [PATCH 0573/1086] Fix TODO --- src/dynamics/attitude/attitude.hpp | 18 +----------------- 1 file changed, 1 insertion(+), 17 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index a6257dae3..fbd342636 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -46,21 +46,6 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Return attitude quaternion from the inertial frame to the body fixed frame */ inline libra::Quaternion GetQuaternion_i2b() const { return quaternion_i2b_; } - /** - * @fn GetDCM_b2i - * @brief Return attitude direction cosine matrix from the body fixed frame to the inertial frame - * @note TODO: Check correctness i2b? b2i? - */ - inline libra::Matrix<3, 3> GetDCM_b2i() const { return quaternion_i2b_.toDCM(); } - /** - * @fn GetDCM_i2b - * @brief Return attitude direction cosine matrix from the inertial frame to the body fixed frame - * @note TODO: Check correctness i2b? b2i? - */ - inline libra::Matrix<3, 3> GetDCM_i2b() const { - libra::Matrix<3, 3> DCM_b2i = quaternion_i2b_.toDCM(); - return transpose(DCM_b2i); - } /** * @fn GetTotalAngMomNorm * @brief Return norm of total angular momentum of the spacecraft [Nms] @@ -69,9 +54,8 @@ class Attitude : public ILoggable, public SimulationObject { /** * @fn GetEnergy * @brief Return rotational Kinetic Energy of Spacecraft [J] - * @note TODO: Consider to use k_sc_J_ */ - inline double GetEnergy() const { return 0.5f * libra::inner_product(omega_b_rad_s_, inertia_tensor_kgm2_ * omega_b_rad_s_); } + inline double GetEnergy() const { return k_sc_J_; } /** * @fn GetInertiaTensor * @brief Return inertia tensor [kg m^2] From 610cbe90f7911be743bb36df1cfec0ede8b848b3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:39:14 +0100 Subject: [PATCH 0574/1086] Integrate private functions --- src/dynamics/attitude/attitude.cpp | 6 ++--- src/dynamics/attitude/attitude.hpp | 35 +++++++++++++------------- src/dynamics/attitude/attitude_rk4.cpp | 8 +++--- 3 files changed, 23 insertions(+), 26 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 58e17ac8e..e80eb1255 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -44,12 +44,12 @@ std::string Attitude::GetLogValue() const { void Attitude::SetParameters(const MCSimExecutor& mc_sim) { GetInitParameterQuaternion(mc_sim, "Q_i2b", quaternion_i2b_); } -void Attitude::CalcAngMom(void) { +void Attitude::CalcAngularMomentum(void) { h_sc_b_Nms_ = inertia_tensor_kgm2_ * omega_b_rad_s_; h_total_b_Nms_ = h_rw_b_Nms_ + h_sc_b_Nms_; Quaternion q_b2i = quaternion_i2b_.conjugate(); h_total_i_Nms_ = q_b2i.frame_conv(h_total_b_Nms_); h_total_Nms_ = norm(h_total_i_Nms_); -} -void Attitude::CalcSatRotationalKineticEnergy(void) { k_sc_J_ = 0.5 * libra::inner_product(h_sc_b_Nms_, omega_b_rad_s_); } + k_sc_J_ = 0.5 * libra::inner_product(h_sc_b_Nms_, omega_b_rad_s_); +} diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index fbd342636..1812ae995 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -88,6 +88,7 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Add quaternion offset rotation */ inline void AddQuaternionOffset(const libra::Quaternion offset) { quaternion_i2b_ = quaternion_i2b_ * offset; } + /** * @fn SetTorque_b * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] @@ -98,6 +99,7 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Add torque acting on the spacecraft on the body fixed frame [Nm] */ inline void AddTorque_b_Nm(const libra::Vector<3> set) { torque_b_Nm_ += set; } + /** * @fn SetAngMom_rw * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] @@ -135,30 +137,27 @@ class Attitude : public ILoggable, public SimulationObject { virtual void SetParameters(const MCSimExecutor& mc_sim); protected: - bool is_calc_enabled_ = true; //!< Calculation flag - double prop_step_s_; //!< Propagation step [sec] - libra::Vector<3> omega_b_rad_s_; //!< Angular velocity of spacecraft body fixed frame with respect to the inertial frame [rad/s] - libra::Quaternion quaternion_i2b_; //!< Attitude quaternion from the inertial frame to the body fixed frame - libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] + bool is_calc_enabled_ = true; //!< Calculation flag + double prop_step_s_; //!< Propagation step [sec] + libra::Vector<3> omega_b_rad_s_; //!< Angular velocity of spacecraft body fixed frame with respect to the inertial frame [rad/s] + libra::Quaternion quaternion_i2b_; //!< Attitude quaternion from the inertial frame to the body fixed frame + libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] + libra::Matrix<3, 3> inertia_tensor_kgm2_; //!< Inertia tensor of the spacecraft [kg m^2] TODO: Move to Structure libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the inertia tensor - libra::Vector<3> h_sc_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] - libra::Vector<3> h_rw_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] - libra::Vector<3> h_total_b_Nms_; //!< Total angular momentum of spacecraft in the body fixed frame [Nms] - libra::Vector<3> h_total_i_Nms_; //!< Total angular momentum of spacecraft in the inertial frame [Nms] - double h_total_Nms_; //!< Norm of total angular momentum [Nms] - double k_sc_J_; //!< Rotational Kinetic Energy of Spacecraft [J] + + libra::Vector<3> h_sc_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] + libra::Vector<3> h_rw_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] + libra::Vector<3> h_total_b_Nms_; //!< Total angular momentum of spacecraft in the body fixed frame [Nms] + libra::Vector<3> h_total_i_Nms_; //!< Total angular momentum of spacecraft in the inertial frame [Nms] + double h_total_Nms_; //!< Norm of total angular momentum [Nms] + double k_sc_J_; //!< Rotational Kinetic Energy of Spacecraft [J] /** - * @fn CalcAngMom + * @fn CalcAngularMomentum * @brief Calculate angular momentum */ - void CalcAngMom(void); - /** - * @fn CalcSatRotationalKineticEnergy - * @brief Calculate rotational Kinetic Energy of Spacecraft - */ - void CalcSatRotationalKineticEnergy(void); + void CalcAngularMomentum(void); }; #endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_HPP_ diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 1998ff286..a5e14db06 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -22,7 +22,7 @@ AttitudeRK4::AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quatern prop_time_s_ = 0.0; inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); h_rw_b_Nms_ = libra::Vector<3>(0.0); - CalcAngMom(); + CalcAngularMomentum(); } AttitudeRK4::~AttitudeRK4() {} @@ -35,8 +35,7 @@ void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { prop_time_s_ = 0.0; inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); h_rw_b_Nms_ = Vector<3>(0.0); //!< Consider how to handle this variable - CalcAngMom(); - CalcSatRotationalKineticEnergy(); + CalcAngularMomentum(); } void AttitudeRK4::Propagate(const double endtime_s) { @@ -48,8 +47,7 @@ void AttitudeRK4::Propagate(const double endtime_s) { RungeOneStep(prop_time_s_, endtime_s - prop_time_s_); prop_time_s_ = endtime_s; - CalcAngMom(); - CalcSatRotationalKineticEnergy(); + CalcAngularMomentum(); } Matrix<4, 4> AttitudeRK4::Omega4Kinematics(Vector<3> omega) { From 6a4e81748763469770e4bc6b9501f896c8abff3f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:43:55 +0100 Subject: [PATCH 0575/1086] Fix function arguments --- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 16 ++++++++-------- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index e80eb1255..e3d396cef 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -47,7 +47,7 @@ void Attitude::SetParameters(const MCSimExecutor& mc_sim) { GetInitParameterQuat void Attitude::CalcAngularMomentum(void) { h_sc_b_Nms_ = inertia_tensor_kgm2_ * omega_b_rad_s_; h_total_b_Nms_ = h_rw_b_Nms_ + h_sc_b_Nms_; - Quaternion q_b2i = quaternion_i2b_.conjugate(); + libra::Quaternion q_b2i = quaternion_i2b_.conjugate(); h_total_i_Nms_ = q_b2i.frame_conv(h_total_b_Nms_); h_total_Nms_ = norm(h_total_i_Nms_); diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 1812ae995..8dd2bfcfe 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -72,17 +72,17 @@ class Attitude : public ILoggable, public SimulationObject { * @fn SetPropStep * @brief Set propagation step [sec] */ - inline void SetPropStep(double set) { prop_step_s_ = set; } + inline void SetPropStep(double prop_step_s) { prop_step_s_ = prop_step_s; } /** * @fn SetOmega_b * @brief Set angular velocity of the body fixed frame with respect to the inertial frame [rad/s] */ - inline void SetOmega_b(const libra::Vector<3> set) { omega_b_rad_s_ = set; } + inline void SetOmega_b(const libra::Vector<3> omega_b_rad_s) { omega_b_rad_s_ = omega_b_rad_s; } /** * @fn SetQuaternion_i2b * @brief Set attitude quaternion from the inertial frame to the body frame */ - inline void SetQuaternion_i2b(const libra::Quaternion set) { quaternion_i2b_ = set; } + inline void SetQuaternion_i2b(const libra::Quaternion quaternion_i2b) { quaternion_i2b_ = quaternion_i2b; } /** * @fn AddQuaternionOffset * @brief Add quaternion offset rotation @@ -93,24 +93,24 @@ class Attitude : public ILoggable, public SimulationObject { * @fn SetTorque_b * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] */ - inline void SetTorque_b(const libra::Vector<3> set) { torque_b_Nm_ = set; } + inline void SetTorque_b(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ = torque_b_Nm; } /** * @fn AddTorque_b_Nm * @brief Add torque acting on the spacecraft on the body fixed frame [Nm] */ - inline void AddTorque_b_Nm(const libra::Vector<3> set) { torque_b_Nm_ += set; } + inline void AddTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ += torque_b_Nm; } /** * @fn SetAngMom_rw * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] */ - inline void SetAngMom_rw(const libra::Vector<3> set) { h_rw_b_Nms_ = set; } + inline void SetAngMom_rw(const libra::Vector<3> h_rw_b_Nms) { h_rw_b_Nms_ = h_rw_b_Nms; } /** * @fn SetInertiaTensor * @brief Set inertia tensor of the spacecraft [kg m2] */ - inline void SetInertiaTensor(const Matrix<3, 3>& set) { - inertia_tensor_kgm2_ = set; + inline void SetInertiaTensor(const Matrix<3, 3>& inertia_tensor_kgm2) { + inertia_tensor_kgm2_ = inertia_tensor_kgm2; inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); } From b2c7c47917abac514847df2ee54cd116a6699327 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:45:49 +0100 Subject: [PATCH 0576/1086] Remove unnecessary public functions --- src/dynamics/attitude/attitude.hpp | 25 ------------------------- 1 file changed, 25 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 8dd2bfcfe..9bdac75aa 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -61,18 +61,8 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Return inertia tensor [kg m^2] */ inline libra::Matrix<3, 3> GetInertiaTensor() const { return inertia_tensor_kgm2_; } - /** - * @fn GetInvInertiaTensor - * @brief Return inverse matrix of inertia tensor - */ - inline libra::Matrix<3, 3> GetInvInertiaTensor() const { return inv_inertia_tensor_; } // Setter - /** - * @fn SetPropStep - * @brief Set propagation step [sec] - */ - inline void SetPropStep(double prop_step_s) { prop_step_s_ = prop_step_s; } /** * @fn SetOmega_b * @brief Set angular velocity of the body fixed frame with respect to the inertial frame [rad/s] @@ -83,12 +73,6 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Set attitude quaternion from the inertial frame to the body frame */ inline void SetQuaternion_i2b(const libra::Quaternion quaternion_i2b) { quaternion_i2b_ = quaternion_i2b; } - /** - * @fn AddQuaternionOffset - * @brief Add quaternion offset rotation - */ - inline void AddQuaternionOffset(const libra::Quaternion offset) { quaternion_i2b_ = quaternion_i2b_ * offset; } - /** * @fn SetTorque_b * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] @@ -99,20 +83,11 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Add torque acting on the spacecraft on the body fixed frame [Nm] */ inline void AddTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ += torque_b_Nm; } - /** * @fn SetAngMom_rw * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] */ inline void SetAngMom_rw(const libra::Vector<3> h_rw_b_Nms) { h_rw_b_Nms_ = h_rw_b_Nms; } - /** - * @fn SetInertiaTensor - * @brief Set inertia tensor of the spacecraft [kg m2] - */ - inline void SetInertiaTensor(const Matrix<3, 3>& inertia_tensor_kgm2) { - inertia_tensor_kgm2_ = inertia_tensor_kgm2; - inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); - } /** * @fn Propagate From b9843d11be0ee44f1e16888d755e3c58409cf0c3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:51:25 +0100 Subject: [PATCH 0577/1086] Fix private variables --- src/dynamics/attitude/attitude.cpp | 30 ++++++++-------- src/dynamics/attitude/attitude.hpp | 34 +++++++++---------- src/dynamics/attitude/attitude_rk4.cpp | 24 ++++++------- src/dynamics/attitude/controlled_attitude.cpp | 8 ++--- 4 files changed, 48 insertions(+), 48 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index e3d396cef..be9649778 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -7,15 +7,15 @@ #include Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { - omega_b_rad_s_ = libra::Vector<3>(0.0); + angular_velocity_b_rad_s_ = libra::Vector<3>(0.0); quaternion_i2b_ = libra::Quaternion(0.0, 0.0, 0.0, 1.0); torque_b_Nm_ = libra::Vector<3>(0.0); - h_sc_b_Nms_ = libra::Vector<3>(0.0); - h_rw_b_Nms_ = libra::Vector<3>(0.0); - h_total_b_Nms_ = libra::Vector<3>(0.0); - h_total_i_Nms_ = libra::Vector<3>(0.0); - h_total_Nms_ = 0.0; - k_sc_J_ = 0.0; + angular_momentum_spacecraft_b_Nms_ = libra::Vector<3>(0.0); + angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); + angular_momentum_total_b_Nms_ = libra::Vector<3>(0.0); + angular_momentum_total_i_Nms_ = libra::Vector<3>(0.0); + angular_momentum_total_Nms_ = 0.0; + kinetic_energy_J_ = 0.0; } std::string Attitude::GetLogHeader() const { @@ -33,11 +33,11 @@ std::string Attitude::GetLogHeader() const { std::string Attitude::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(omega_b_rad_s_); + str_tmp += WriteVector(angular_velocity_b_rad_s_); str_tmp += WriteQuaternion(quaternion_i2b_); str_tmp += WriteVector(torque_b_Nm_); - str_tmp += WriteScalar(h_total_Nms_); - str_tmp += WriteScalar(k_sc_J_); + str_tmp += WriteScalar(angular_momentum_total_Nms_); + str_tmp += WriteScalar(kinetic_energy_J_); return str_tmp; } @@ -45,11 +45,11 @@ std::string Attitude::GetLogValue() const { void Attitude::SetParameters(const MCSimExecutor& mc_sim) { GetInitParameterQuaternion(mc_sim, "Q_i2b", quaternion_i2b_); } void Attitude::CalcAngularMomentum(void) { - h_sc_b_Nms_ = inertia_tensor_kgm2_ * omega_b_rad_s_; - h_total_b_Nms_ = h_rw_b_Nms_ + h_sc_b_Nms_; + angular_momentum_spacecraft_b_Nms_ = inertia_tensor_kgm2_ * angular_velocity_b_rad_s_; + angular_momentum_total_b_Nms_ = angular_momentum_reaction_wheel_b_Nms_ + angular_momentum_spacecraft_b_Nms_; libra::Quaternion q_b2i = quaternion_i2b_.conjugate(); - h_total_i_Nms_ = q_b2i.frame_conv(h_total_b_Nms_); - h_total_Nms_ = norm(h_total_i_Nms_); + angular_momentum_total_i_Nms_ = q_b2i.frame_conv(angular_momentum_total_b_Nms_); + angular_momentum_total_Nms_ = norm(angular_momentum_total_i_Nms_); - k_sc_J_ = 0.5 * libra::inner_product(h_sc_b_Nms_, omega_b_rad_s_); + kinetic_energy_J_ = 0.5 * libra::inner_product(angular_momentum_spacecraft_b_Nms_, angular_velocity_b_rad_s_); } diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 9bdac75aa..6768d7807 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -35,12 +35,12 @@ class Attitude : public ILoggable, public SimulationObject { * @fn GetPropStep * @brief Return propagation step [sec] */ - inline double GetPropStep() const { return prop_step_s_; } + inline double GetPropStep() const { return propagation_step_s_; } /** * @fn GetOmega_b * @brief Return angular velocity of spacecraft body-fixed frame with respect to the inertial frame [rad/s] */ - inline libra::Vector<3> GetOmega_b() const { return omega_b_rad_s_; } + inline libra::Vector<3> GetOmega_b() const { return angular_velocity_b_rad_s_; } /** * @fn GetQuaternion_i2b * @brief Return attitude quaternion from the inertial frame to the body fixed frame @@ -50,12 +50,12 @@ class Attitude : public ILoggable, public SimulationObject { * @fn GetTotalAngMomNorm * @brief Return norm of total angular momentum of the spacecraft [Nms] */ - inline double GetTotalAngMomNorm() const { return libra::norm(h_total_b_Nms_); } + inline double GetTotalAngMomNorm() const { return libra::norm(angular_momentum_total_b_Nms_); } /** * @fn GetEnergy * @brief Return rotational Kinetic Energy of Spacecraft [J] */ - inline double GetEnergy() const { return k_sc_J_; } + inline double GetEnergy() const { return kinetic_energy_J_; } /** * @fn GetInertiaTensor * @brief Return inertia tensor [kg m^2] @@ -67,7 +67,7 @@ class Attitude : public ILoggable, public SimulationObject { * @fn SetOmega_b * @brief Set angular velocity of the body fixed frame with respect to the inertial frame [rad/s] */ - inline void SetOmega_b(const libra::Vector<3> omega_b_rad_s) { omega_b_rad_s_ = omega_b_rad_s; } + inline void SetOmega_b(const libra::Vector<3> omega_b_rad_s) { angular_velocity_b_rad_s_ = omega_b_rad_s; } /** * @fn SetQuaternion_i2b * @brief Set attitude quaternion from the inertial frame to the body frame @@ -87,7 +87,7 @@ class Attitude : public ILoggable, public SimulationObject { * @fn SetAngMom_rw * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] */ - inline void SetAngMom_rw(const libra::Vector<3> h_rw_b_Nms) { h_rw_b_Nms_ = h_rw_b_Nms; } + inline void SetAngMom_rw(const libra::Vector<3> angular_momentum_rw_b_Nms) { angular_momentum_reaction_wheel_b_Nms_ = angular_momentum_rw_b_Nms; } /** * @fn Propagate @@ -112,21 +112,21 @@ class Attitude : public ILoggable, public SimulationObject { virtual void SetParameters(const MCSimExecutor& mc_sim); protected: - bool is_calc_enabled_ = true; //!< Calculation flag - double prop_step_s_; //!< Propagation step [sec] - libra::Vector<3> omega_b_rad_s_; //!< Angular velocity of spacecraft body fixed frame with respect to the inertial frame [rad/s] - libra::Quaternion quaternion_i2b_; //!< Attitude quaternion from the inertial frame to the body fixed frame - libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] + bool is_calc_enabled_ = true; //!< Calculation flag + double propagation_step_s_; //!< Propagation step [sec] + libra::Vector<3> angular_velocity_b_rad_s_; //!< Angular velocity of spacecraft body fixed frame with respect to the inertial frame [rad/s] + libra::Quaternion quaternion_i2b_; //!< Attitude quaternion from the inertial frame to the body fixed frame + libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] libra::Matrix<3, 3> inertia_tensor_kgm2_; //!< Inertia tensor of the spacecraft [kg m^2] TODO: Move to Structure libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the inertia tensor - libra::Vector<3> h_sc_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] - libra::Vector<3> h_rw_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] - libra::Vector<3> h_total_b_Nms_; //!< Total angular momentum of spacecraft in the body fixed frame [Nms] - libra::Vector<3> h_total_i_Nms_; //!< Total angular momentum of spacecraft in the inertial frame [Nms] - double h_total_Nms_; //!< Norm of total angular momentum [Nms] - double k_sc_J_; //!< Rotational Kinetic Energy of Spacecraft [J] + libra::Vector<3> angular_momentum_spacecraft_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] + libra::Vector<3> angular_momentum_reaction_wheel_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] + libra::Vector<3> angular_momentum_total_b_Nms_; //!< Total angular momentum of spacecraft in the body fixed frame [Nms] + libra::Vector<3> angular_momentum_total_i_Nms_; //!< Total angular momentum of spacecraft in the inertial frame [Nms] + double angular_momentum_total_Nms_; //!< Norm of total angular momentum [Nms] + double kinetic_energy_J_; //!< Rotational Kinetic Energy of Spacecraft [J] /** * @fn CalcAngularMomentum diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index a5e14db06..e6d57bda3 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -14,14 +14,14 @@ using namespace std; AttitudeRK4::AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quaternion_i2b_ini, const Matrix<3, 3>& InertiaTensor_ini, const Vector<3>& torque_b_ini, const double prop_step_ini, const std::string& sim_object_name) : Attitude(sim_object_name) { - omega_b_rad_s_ = omega_b_ini; + angular_velocity_b_rad_s_ = omega_b_ini; quaternion_i2b_ = quaternion_i2b_ini; torque_b_Nm_ = torque_b_ini; inertia_tensor_kgm2_ = InertiaTensor_ini; - prop_step_s_ = prop_step_ini; + propagation_step_s_ = prop_step_ini; prop_time_s_ = 0.0; inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); - h_rw_b_Nms_ = libra::Vector<3>(0.0); + angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); CalcAngularMomentum(); } @@ -29,20 +29,20 @@ AttitudeRK4::~AttitudeRK4() {} void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { Attitude::SetParameters(mc_sim); - GetInitParameterVec(mc_sim, "Omega_b", omega_b_rad_s_); + GetInitParameterVec(mc_sim, "Omega_b", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? prop_time_s_ = 0.0; inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); - h_rw_b_Nms_ = Vector<3>(0.0); //!< Consider how to handle this variable + angular_momentum_reaction_wheel_b_Nms_ = Vector<3>(0.0); //!< Consider how to handle this variable CalcAngularMomentum(); } void AttitudeRK4::Propagate(const double endtime_s) { if (!is_calc_enabled_) return; - while (endtime_s - prop_time_s_ - prop_step_s_ > 1.0e-6) { - RungeOneStep(prop_time_s_, prop_step_s_); - prop_time_s_ += prop_step_s_; + while (endtime_s - prop_time_s_ - propagation_step_s_ > 1.0e-6) { + RungeOneStep(prop_time_s_, propagation_step_s_); + prop_time_s_ += propagation_step_s_; } RungeOneStep(prop_time_s_, endtime_s - prop_time_s_); prop_time_s_ = endtime_s; @@ -82,8 +82,8 @@ Vector<7> AttitudeRK4::DynamicsKinematics(Vector<7> x, double t) { for (int i = 0; i < 3; i++) { omega_b[i] = x[i]; } - h_total_b_Nms_ = (inertia_tensor_kgm2_ * omega_b) + h_rw_b_Nms_; - Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::outer_product(omega_b, h_total_b_Nms_)); + angular_momentum_total_b_Nms_ = (inertia_tensor_kgm2_ * omega_b) + angular_momentum_reaction_wheel_b_Nms_; + Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::outer_product(omega_b, angular_momentum_total_b_Nms_)); for (int i = 0; i < 3; ++i) { dxdt[i] = rhs[i]; @@ -106,7 +106,7 @@ Vector<7> AttitudeRK4::DynamicsKinematics(Vector<7> x, double t) { void AttitudeRK4::RungeOneStep(double t, double dt) { Vector<7> x; for (int i = 0; i < 3; i++) { - x[i] = omega_b_rad_s_[i]; + x[i] = angular_velocity_b_rad_s_[i]; } for (int i = 0; i < 4; i++) { x[i + 3] = quaternion_i2b_[i]; @@ -129,7 +129,7 @@ void AttitudeRK4::RungeOneStep(double t, double dt) { Vector<7> next_x = x + (dt / 6.0) * (k1 + 2.0 * k2 + 2.0 * k3 + k4); for (int i = 0; i < 3; i++) { - omega_b_rad_s_[i] = next_x[i]; + angular_velocity_b_rad_s_[i] = next_x[i]; } for (int i = 0; i < 4; i++) { quaternion_i2b_[i] = next_x[i + 3]; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 0c8674bcd..be150a3d4 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -151,12 +151,12 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { libra::Vector<3> angular_acc_b_rad_s2_; for (int i = 0; i < 3; i++) { - omega_b_rad_s_[i] = q_diff[i]; - angular_acc_b_rad_s2_[i] = (prev_omega_b_rad_s_[i] - omega_b_rad_s_[i]) / time_diff_sec; + angular_velocity_b_rad_s_[i] = q_diff[i]; + angular_acc_b_rad_s2_[i] = (prev_omega_b_rad_s_[i] - angular_velocity_b_rad_s_[i]) / time_diff_sec; } controlled_torque_b_Nm = inv_inertia_tensor_ * angular_acc_b_rad_s2_; } else { - omega_b_rad_s_ = libra::Vector<3>(0.0); + angular_velocity_b_rad_s_ = libra::Vector<3>(0.0); controlled_torque_b_Nm = libra::Vector<3>(0.0); } // Add torque with disturbances @@ -164,5 +164,5 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { // save previous values previous_calc_time_s_ = current_time_s; prev_quaternion_i2b_ = quaternion_i2b_; - prev_omega_b_rad_s_ = omega_b_rad_s_; + prev_omega_b_rad_s_ = angular_velocity_b_rad_s_; } From 40dc7404b893a553597a9df773d64321310d291e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 16:58:20 +0100 Subject: [PATCH 0578/1086] Fix private functions --- src/dynamics/attitude/attitude_rk4.cpp | 70 +++++++++++++------------- src/dynamics/attitude/attitude_rk4.hpp | 20 ++++---- 2 files changed, 45 insertions(+), 45 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index e6d57bda3..0dbd4b41b 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -19,7 +19,7 @@ AttitudeRK4::AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quatern torque_b_Nm_ = torque_b_ini; inertia_tensor_kgm2_ = InertiaTensor_ini; propagation_step_s_ = prop_step_ini; - prop_time_s_ = 0.0; + current_propagation_time_s_ = 0.0; inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); CalcAngularMomentum(); @@ -32,7 +32,7 @@ void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { GetInitParameterVec(mc_sim, "Omega_b", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? - prop_time_s_ = 0.0; + current_propagation_time_s_ = 0.0; inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); angular_momentum_reaction_wheel_b_Nms_ = Vector<3>(0.0); //!< Consider how to handle this variable CalcAngularMomentum(); @@ -40,40 +40,40 @@ void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { void AttitudeRK4::Propagate(const double endtime_s) { if (!is_calc_enabled_) return; - while (endtime_s - prop_time_s_ - propagation_step_s_ > 1.0e-6) { - RungeOneStep(prop_time_s_, propagation_step_s_); - prop_time_s_ += propagation_step_s_; + while (endtime_s - current_propagation_time_s_ - propagation_step_s_ > 1.0e-6) { + RungeKuttaOneStep(current_propagation_time_s_, propagation_step_s_); + current_propagation_time_s_ += propagation_step_s_; } - RungeOneStep(prop_time_s_, endtime_s - prop_time_s_); - prop_time_s_ = endtime_s; + RungeKuttaOneStep(current_propagation_time_s_, endtime_s - current_propagation_time_s_); + current_propagation_time_s_ = endtime_s; CalcAngularMomentum(); } -Matrix<4, 4> AttitudeRK4::Omega4Kinematics(Vector<3> omega) { - Matrix<4, 4> OMEGA; - - OMEGA[0][0] = 0.0f; - OMEGA[0][1] = omega[2]; - OMEGA[0][2] = -omega[1]; - OMEGA[0][3] = omega[0]; - OMEGA[1][0] = -omega[2]; - OMEGA[1][1] = 0.0f; - OMEGA[1][2] = omega[0]; - OMEGA[1][3] = omega[1]; - OMEGA[2][0] = omega[1]; - OMEGA[2][1] = -omega[0]; - OMEGA[2][2] = 0.0f; - OMEGA[2][3] = omega[2]; - OMEGA[3][0] = -omega[0]; - OMEGA[3][1] = -omega[1]; - OMEGA[3][2] = -omega[2]; - OMEGA[3][3] = 0.0f; - - return OMEGA; +Matrix<4, 4> AttitudeRK4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s) { + Matrix<4, 4> angular_velocity_matrix; + + angular_velocity_matrix[0][0] = 0.0f; + angular_velocity_matrix[0][1] = angular_velocity_b_rad_s[2]; + angular_velocity_matrix[0][2] = -angular_velocity_b_rad_s[1]; + angular_velocity_matrix[0][3] = angular_velocity_b_rad_s[0]; + angular_velocity_matrix[1][0] = -angular_velocity_b_rad_s[2]; + angular_velocity_matrix[1][1] = 0.0f; + angular_velocity_matrix[1][2] = angular_velocity_b_rad_s[0]; + angular_velocity_matrix[1][3] = angular_velocity_b_rad_s[1]; + angular_velocity_matrix[2][0] = angular_velocity_b_rad_s[1]; + angular_velocity_matrix[2][1] = -angular_velocity_b_rad_s[0]; + angular_velocity_matrix[2][2] = 0.0f; + angular_velocity_matrix[2][3] = angular_velocity_b_rad_s[2]; + angular_velocity_matrix[3][0] = -angular_velocity_b_rad_s[0]; + angular_velocity_matrix[3][1] = -angular_velocity_b_rad_s[1]; + angular_velocity_matrix[3][2] = -angular_velocity_b_rad_s[2]; + angular_velocity_matrix[3][3] = 0.0f; + + return angular_velocity_matrix; } -Vector<7> AttitudeRK4::DynamicsKinematics(Vector<7> x, double t) { +Vector<7> AttitudeRK4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { UNUSED(t); Vector<7> dxdt; @@ -94,7 +94,7 @@ Vector<7> AttitudeRK4::DynamicsKinematics(Vector<7> x, double t) { quaternion_i2b[i] = x[i + 3]; } - Vector<4> d_quaternion = 0.5 * Omega4Kinematics(omega_b) * quaternion_i2b; + Vector<4> d_quaternion = 0.5 * CalcAngularVelocityMatrix(omega_b) * quaternion_i2b; for (int i = 0; i < 4; i++) { dxdt[i + 3] = d_quaternion[i]; @@ -103,7 +103,7 @@ Vector<7> AttitudeRK4::DynamicsKinematics(Vector<7> x, double t) { return dxdt; } -void AttitudeRK4::RungeOneStep(double t, double dt) { +void AttitudeRK4::RungeKuttaOneStep(double t, double dt) { Vector<7> x; for (int i = 0; i < 3; i++) { x[i] = angular_velocity_b_rad_s_[i]; @@ -115,16 +115,16 @@ void AttitudeRK4::RungeOneStep(double t, double dt) { Vector<7> k1, k2, k3, k4; Vector<7> xk2, xk3, xk4; - k1 = DynamicsKinematics(x, t); + k1 = AttitudeDynamicsAndKinematics(x, t); xk2 = x + (dt / 2.0) * k1; - k2 = DynamicsKinematics(xk2, (t + dt / 2.0)); + k2 = AttitudeDynamicsAndKinematics(xk2, (t + dt / 2.0)); xk3 = x + (dt / 2.0) * k2; - k3 = DynamicsKinematics(xk3, (t + dt / 2.0)); + k3 = AttitudeDynamicsAndKinematics(xk3, (t + dt / 2.0)); xk4 = x + dt * k3; - k4 = DynamicsKinematics(xk4, (t + dt)); + k4 = AttitudeDynamicsAndKinematics(xk4, (t + dt)); Vector<7> next_x = x + (dt / 6.0) * (k1 + 2.0 * k2 + 2.0 * k3 + k4); diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index 88600bf1d..54d582b0c 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -36,13 +36,13 @@ class AttitudeRK4 : public Attitude { * @fn GetPropTime * @brief Return propagation time (current time) [sec] */ - inline double GetPropTime() const { return prop_time_s_; } + inline double GetPropTime() const { return current_propagation_time_s_; } /** * @fn SetTime * @brief Set propagation time (current time) [sec] */ - inline void SetTime(double set) { prop_time_s_ = set; } + inline void SetTime(double set) { current_propagation_time_s_ = set; } /** * @fn Propagate @@ -59,28 +59,28 @@ class AttitudeRK4 : public Attitude { virtual void SetParameters(const MCSimExecutor& mc_sim); private: - double prop_time_s_; //!< current time [sec] + double current_propagation_time_s_; //!< current time [sec] /** - * @fn Omega4Kinematics + * @fn CalcAngularVelocityMatrix * @brief Generate angular velocity matrix for kinematics calculation - * @param [in] omega: Angular velocity [rad/s] + * @param [in] angular_velocity_b_rad_s: Angular velocity [rad/s] */ - Matrix<4, 4> Omega4Kinematics(Vector<3> omega); + Matrix<4, 4> CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s); /** - * @fn DynamicsKinematics + * @fn AttitudeDynamicsAndKinematics * @brief Dynamics equation with kinematics * @param [in] x: State vector (angular velocity and quaternion) * @param [in] t: Unused TODO: remove? */ - Vector<7> DynamicsKinematics(Vector<7> x, double t); + Vector<7> AttitudeDynamicsAndKinematics(Vector<7> x, double t); /** - * @fn RungeOneStep + * @fn RungeKuttaOneStep * @brief Equation for one step of Runge-Kutta method * @param [in] t: Unused TODO: remove? * @param [in] dt: Step width [sec] */ - void RungeOneStep(double t, double dt); + void RungeKuttaOneStep(double t, double dt); }; #endif // S2E_DYNAMICS_ATTITUDE_ATTITUDE_RK4_HPP_ From 1b9e32ea59451b07e1bdcf22113a04256b229063 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 18:44:59 +0100 Subject: [PATCH 0579/1086] Fix function argument --- src/dynamics/attitude/attitude.cpp | 4 +-- src/dynamics/attitude/attitude.hpp | 10 +++---- src/dynamics/attitude/attitude_rk4.cpp | 30 +++++++++---------- src/dynamics/attitude/attitude_rk4.hpp | 24 +++++++-------- src/dynamics/attitude/controlled_attitude.cpp | 9 +++--- src/dynamics/attitude/controlled_attitude.hpp | 8 ++--- 6 files changed, 43 insertions(+), 42 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index be9649778..96311b4cc 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -6,7 +6,7 @@ #include -Attitude::Attitude(const std::string& sim_object_name) : SimulationObject(sim_object_name) { +Attitude::Attitude(const std::string& simulation_object_name) : SimulationObject(simulation_object_name) { angular_velocity_b_rad_s_ = libra::Vector<3>(0.0); quaternion_i2b_ = libra::Quaternion(0.0, 0.0, 0.0, 1.0); torque_b_Nm_ = libra::Vector<3>(0.0); @@ -42,7 +42,7 @@ std::string Attitude::GetLogValue() const { return str_tmp; } -void Attitude::SetParameters(const MCSimExecutor& mc_sim) { GetInitParameterQuaternion(mc_sim, "Q_i2b", quaternion_i2b_); } +void Attitude::SetParameters(const MCSimExecutor& mc_simulator) { GetInitParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); } void Attitude::CalcAngularMomentum(void) { angular_momentum_spacecraft_b_Nms_ = inertia_tensor_kgm2_ * angular_velocity_b_rad_s_; diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 6768d7807..b25997043 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -21,9 +21,9 @@ class Attitude : public ILoggable, public SimulationObject { /** * @fn Attitude * @brief Constructor - * @param [in] sim_object_name: Simulation object name for Monte-Carlo simulation + * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - Attitude(const std::string& sim_object_name = "Attitude"); + Attitude(const std::string& simulation_object_name = "Attitude"); /** * @fn ~Attitude * @brief Destructor @@ -92,9 +92,9 @@ class Attitude : public ILoggable, public SimulationObject { /** * @fn Propagate * @brief Pure virtual function of attitude propagation - * @param [in] endtime_s: Propagation endtime [sec] + * @param [in] end_time_s: Propagation endtime [sec] */ - virtual void Propagate(const double endtime_s) = 0; + virtual void Propagate(const double end_time_s) = 0; // Override ILoggable /** @@ -109,7 +109,7 @@ class Attitude : public ILoggable, public SimulationObject { virtual std::string GetLogValue() const; // SimulationObject for McSim - virtual void SetParameters(const MCSimExecutor& mc_sim); + virtual void SetParameters(const MCSimExecutor& mc_simulator); protected: bool is_calc_enabled_ = true; //!< Calculation flag diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 0dbd4b41b..fbaa45e6f 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -11,14 +11,14 @@ using namespace std; #include #include -AttitudeRK4::AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quaternion_i2b_ini, const Matrix<3, 3>& InertiaTensor_ini, - const Vector<3>& torque_b_ini, const double prop_step_ini, const std::string& sim_object_name) - : Attitude(sim_object_name) { - angular_velocity_b_rad_s_ = omega_b_ini; - quaternion_i2b_ = quaternion_i2b_ini; - torque_b_Nm_ = torque_b_ini; - inertia_tensor_kgm2_ = InertiaTensor_ini; - propagation_step_s_ = prop_step_ini; +AttitudeRK4::AttitudeRK4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, + const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name) + : Attitude(simulation_object_name) { + angular_velocity_b_rad_s_ = angular_velocity_b_rad_s; + quaternion_i2b_ = quaternion_i2b; + torque_b_Nm_ = torque_b_Nm; + inertia_tensor_kgm2_ = inertia_tensor_kgm2; + propagation_step_s_ = propagation_step_s; current_propagation_time_s_ = 0.0; inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); @@ -27,9 +27,9 @@ AttitudeRK4::AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quatern AttitudeRK4::~AttitudeRK4() {} -void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { - Attitude::SetParameters(mc_sim); - GetInitParameterVec(mc_sim, "Omega_b", angular_velocity_b_rad_s_); +void AttitudeRK4::SetParameters(const MCSimExecutor& mc_simulator) { + Attitude::SetParameters(mc_simulator); + GetInitParameterVec(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; @@ -38,14 +38,14 @@ void AttitudeRK4::SetParameters(const MCSimExecutor& mc_sim) { CalcAngularMomentum(); } -void AttitudeRK4::Propagate(const double endtime_s) { +void AttitudeRK4::Propagate(const double end_time_s) { if (!is_calc_enabled_) return; - while (endtime_s - current_propagation_time_s_ - propagation_step_s_ > 1.0e-6) { + while (end_time_s - current_propagation_time_s_ - propagation_step_s_ > 1.0e-6) { RungeKuttaOneStep(current_propagation_time_s_, propagation_step_s_); current_propagation_time_s_ += propagation_step_s_; } - RungeKuttaOneStep(current_propagation_time_s_, endtime_s - current_propagation_time_s_); - current_propagation_time_s_ = endtime_s; + RungeKuttaOneStep(current_propagation_time_s_, end_time_s - current_propagation_time_s_); + current_propagation_time_s_ = end_time_s; CalcAngularMomentum(); } diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index 54d582b0c..aa5dd60af 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -17,15 +17,15 @@ class AttitudeRK4 : public Attitude { /** * @fn AttitudeRK4 * @brief Constructor - * @param [in] omega_b_ini: Initial value of spacecraft angular velocity of the body fixed frame [rad/s] - * @param [in] quaternion_i2b_ini: Initial value of attitude quaternion from the inertial frame to the body fixed frame - * @param [in] InertiaTensor_ini: Initial value of inertia tensor of the spacecraft [kg m^2] - * @param [in] torque_b_ini: Initial torque acting on the spacecraft in the body fixed frame [Nm] - * @param [in] prop_step_ini: Initial value of propagation step width [sec] - * @param [in] sim_object_name: Simulation object name for Monte-Carlo simulation + * @param [in] angular_velocity_b_rad_s: Initial value of spacecraft angular velocity of the body fixed frame [rad/s] + * @param [in] quaternion_i2b: Initial value of attitude quaternion from the inertial frame to the body fixed frame + * @param [in] inertia_tensor_kgm2: Initial value of inertia tensor of the spacecraft [kg m^2] + * @param [in] torque_b_Nm: Initial torque acting on the spacecraft in the body fixed frame [Nm] + * @param [in] propagation_step_s: Initial value of propagation step width [sec] + * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - AttitudeRK4(const Vector<3>& omega_b_ini, const Quaternion& quaternion_i2b_ini, const Matrix<3, 3>& InertiaTensor_ini, - const Vector<3>& torque_b_ini, const double prop_step_ini, const std::string& sim_object_name = "Attitude"); + AttitudeRK4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, + const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name = "Attitude"); /** * @fn ~AttitudeRK4 * @brief Destructor @@ -47,16 +47,16 @@ class AttitudeRK4 : public Attitude { /** * @fn Propagate * @brief Attitude propagation - * @param [in] endtime_s: Propagation endtime [sec] + * @param [in] end_time_s: Propagation endtime [sec] */ - virtual void Propagate(const double endtime_s); + virtual void Propagate(const double end_time_s); /** * @fn SetParameters * @brief Set parameters for Monte-Carlo simulation - * @param [in] mc_sim: Monte-Carlo simulation executor + * @param [in] mc_simulator: Monte-Carlo simulation executor */ - virtual void SetParameters(const MCSimExecutor& mc_sim); + virtual void SetParameters(const MCSimExecutor& mc_simulator); private: double current_propagation_time_s_; //!< current time [sec] diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index be150a3d4..0ac713c42 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -14,8 +14,9 @@ using namespace std; ControlledAttitude::ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, const Vector<3> pointing_t_b, const Vector<3> pointing_sub_t_b, const Matrix<3, 3>& inertia_tensor_kgm2, - const LocalCelestialInformation* local_celes_info, const Orbit* orbit, const std::string& sim_object_name) - : Attitude(sim_object_name), + const LocalCelestialInformation* local_celes_info, const Orbit* orbit, + const std::string& simulation_object_name) + : Attitude(simulation_object_name), main_mode_(main_mode), sub_mode_(sub_mode), pointing_t_b_(pointing_t_b), @@ -58,7 +59,7 @@ void ControlledAttitude::Initialize(void) { return; } -void ControlledAttitude::Propagate(const double endtime_s) { +void ControlledAttitude::Propagate(const double end_time_s) { Vector<3> main_direction_i, sub_direction_i; if (!is_calc_enabled_) return; @@ -74,7 +75,7 @@ void ControlledAttitude::Propagate(const double endtime_s) { // Calc attitude PointingCtrl(main_direction_i, sub_direction_i); // Calc angular velocity - CalcAngularVelocity(endtime_s); + CalcAngularVelocity(end_time_s); return; } diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index ec02f6122..04bd7a6f7 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -50,11 +50,11 @@ class ControlledAttitude : public Attitude { * @param [in] inertia_tensor_kgm2: Inertia tensor of the spacecraft [kg m^2] * @param [in] local_celes_info: Local celestial information * @param [in] orbit: Orbit - * @param [in] sim_object_name: Simulation object name for Monte-Carlo simulation + * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, const Vector<3> pointing_t_b, const Vector<3> pointing_sub_t_b, const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celes_info, - const Orbit* orbit, const std::string& sim_object_name = "Attitude"); + const Orbit* orbit, const std::string& simulation_object_name = "Attitude"); /** * @fn ~ControlledAttitude * @brief Destructor @@ -91,9 +91,9 @@ class ControlledAttitude : public Attitude { /** * @fn Propagate * @brief Attitude propagation - * @param [in] endtime_s: Propagation endtime [sec] + * @param [in] end_time_s: Propagation endtime [sec] */ - virtual void Propagate(const double endtime_s); + virtual void Propagate(const double end_time_s); private: AttCtrlMode main_mode_; //!< Main control mode From 9800bf07a1dc0c388b9318bcffeb96d70c332419 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 18:45:41 +0100 Subject: [PATCH 0580/1086] Remove unused public functions --- src/dynamics/attitude/attitude_rk4.hpp | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index aa5dd60af..5cf7e9396 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -32,18 +32,6 @@ class AttitudeRK4 : public Attitude { */ ~AttitudeRK4(); - /** - * @fn GetPropTime - * @brief Return propagation time (current time) [sec] - */ - inline double GetPropTime() const { return current_propagation_time_s_; } - - /** - * @fn SetTime - * @brief Set propagation time (current time) [sec] - */ - inline void SetTime(double set) { current_propagation_time_s_ = set; } - /** * @fn Propagate * @brief Attitude propagation From a290f8375694e7a08501cd18c346133951ca24fe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 18:46:43 +0100 Subject: [PATCH 0581/1086] Rename AttitudeRK4 to AttitudeRk4 --- src/dynamics/attitude/attitude_rk4.cpp | 14 +++++++------- src/dynamics/attitude/attitude_rk4.hpp | 12 ++++++------ src/dynamics/attitude/initialize_attitude.cpp | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index fbaa45e6f..465019404 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -11,7 +11,7 @@ using namespace std; #include #include -AttitudeRK4::AttitudeRK4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, +AttitudeRk4::AttitudeRk4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name) : Attitude(simulation_object_name) { angular_velocity_b_rad_s_ = angular_velocity_b_rad_s; @@ -25,9 +25,9 @@ AttitudeRK4::AttitudeRK4(const Vector<3>& angular_velocity_b_rad_s, const Quater CalcAngularMomentum(); } -AttitudeRK4::~AttitudeRK4() {} +AttitudeRk4::~AttitudeRk4() {} -void AttitudeRK4::SetParameters(const MCSimExecutor& mc_simulator) { +void AttitudeRk4::SetParameters(const MCSimExecutor& mc_simulator) { Attitude::SetParameters(mc_simulator); GetInitParameterVec(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); @@ -38,7 +38,7 @@ void AttitudeRK4::SetParameters(const MCSimExecutor& mc_simulator) { CalcAngularMomentum(); } -void AttitudeRK4::Propagate(const double end_time_s) { +void AttitudeRk4::Propagate(const double end_time_s) { if (!is_calc_enabled_) return; while (end_time_s - current_propagation_time_s_ - propagation_step_s_ > 1.0e-6) { RungeKuttaOneStep(current_propagation_time_s_, propagation_step_s_); @@ -50,7 +50,7 @@ void AttitudeRK4::Propagate(const double end_time_s) { CalcAngularMomentum(); } -Matrix<4, 4> AttitudeRK4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s) { +Matrix<4, 4> AttitudeRk4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s) { Matrix<4, 4> angular_velocity_matrix; angular_velocity_matrix[0][0] = 0.0f; @@ -73,7 +73,7 @@ Matrix<4, 4> AttitudeRK4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b return angular_velocity_matrix; } -Vector<7> AttitudeRK4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { +Vector<7> AttitudeRk4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { UNUSED(t); Vector<7> dxdt; @@ -103,7 +103,7 @@ Vector<7> AttitudeRK4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { return dxdt; } -void AttitudeRK4::RungeKuttaOneStep(double t, double dt) { +void AttitudeRk4::RungeKuttaOneStep(double t, double dt) { Vector<7> x; for (int i = 0; i < 3; i++) { x[i] = angular_velocity_b_rad_s_[i]; diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index 5cf7e9396..b7324e9ef 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -9,13 +9,13 @@ #include "attitude.hpp" /** - * @class AttitudeRK4 + * @class AttitudeRk4 * @brief Class to calculate spacecraft attitude with Runge-Kutta method */ -class AttitudeRK4 : public Attitude { +class AttitudeRk4 : public Attitude { public: /** - * @fn AttitudeRK4 + * @fn AttitudeRk4 * @brief Constructor * @param [in] angular_velocity_b_rad_s: Initial value of spacecraft angular velocity of the body fixed frame [rad/s] * @param [in] quaternion_i2b: Initial value of attitude quaternion from the inertial frame to the body fixed frame @@ -24,13 +24,13 @@ class AttitudeRK4 : public Attitude { * @param [in] propagation_step_s: Initial value of propagation step width [sec] * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - AttitudeRK4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, + AttitudeRk4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name = "Attitude"); /** - * @fn ~AttitudeRK4 + * @fn ~AttitudeRk4 * @brief Destructor */ - ~AttitudeRK4(); + ~AttitudeRk4(); /** * @fn Propagate diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 22277a2a6..6448d27d9 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -24,7 +24,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); - attitude = new AttitudeRK4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); } else if (propagate_mode == "CONTROLLED") { // Controlled attitude IniAccess ini_file_ca(file_name); @@ -52,7 +52,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); - attitude = new AttitudeRK4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); } return attitude; From 308ebf2575524281a286bd2e4dc0983a27495d2c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 18:54:07 +0100 Subject: [PATCH 0582/1086] Fix private variables and function argument names --- src/dynamics/attitude/controlled_attitude.cpp | 32 ++++++++-------- src/dynamics/attitude/controlled_attitude.hpp | 37 ++++++++++--------- src/dynamics/attitude/initialize_attitude.cpp | 10 ++--- 3 files changed, 40 insertions(+), 39 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 0ac713c42..8a692799a 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -13,15 +13,15 @@ using namespace std; #define THRESHOLD_CA cos(30.0 / 180.0 * libra::pi) // fix me ControlledAttitude::ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, - const Vector<3> pointing_t_b, const Vector<3> pointing_sub_t_b, const Matrix<3, 3>& inertia_tensor_kgm2, - const LocalCelestialInformation* local_celes_info, const Orbit* orbit, - const std::string& simulation_object_name) + const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, + const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, + const Orbit* orbit, const std::string& simulation_object_name) : Attitude(simulation_object_name), main_mode_(main_mode), sub_mode_(sub_mode), - pointing_t_b_(pointing_t_b), - pointing_sub_t_b_(pointing_sub_t_b), - local_celes_info_(local_celes_info), + main_target_direction_b_(main_target_direction_b), + sub_target_direction_b_(sub_target_direction_b), + local_celestial_information_(local_celestial_information), orbit_(orbit) { quaternion_i2b_ = quaternion_i2b; inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: inertia tensor should be initialized in the Attitude base class @@ -46,9 +46,9 @@ void ControlledAttitude::Initialize(void) { return; } // pointing direction check - normalize(pointing_t_b_); - normalize(pointing_sub_t_b_); - double tmp = inner_product(pointing_t_b_, pointing_sub_t_b_); + normalize(main_target_direction_b_); + normalize(sub_target_direction_b_); + double tmp = inner_product(main_target_direction_b_, sub_target_direction_b_); tmp = std::abs(tmp); if (tmp > THRESHOLD_CA) { cout << "sub target direction should separate from the main target direction. \n"; @@ -82,9 +82,9 @@ void ControlledAttitude::Propagate(const double end_time_s) { Vector<3> ControlledAttitude::CalcTargetDirection(AttCtrlMode mode) { Vector<3> direction; if (mode == SUN_POINTING) { - direction = local_celes_info_->GetPositionFromSpacecraft_i_m("SUN"); + direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); } else if (mode == EARTH_CENTER_POINTING) { - direction = local_celes_info_->GetPositionFromSpacecraft_i_m("EARTH"); + direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("EARTH"); } else if (mode == VELOCITY_DIRECTION_POINTING) { direction = orbit_->GetSatVelocity_i(); } else if (mode == ORBIT_NORMAL_POINTING) { @@ -98,7 +98,7 @@ void ControlledAttitude::PointingCtrl(const Vector<3> main_direction_i, const Ve // Calc DCM ECI->Target Matrix<3, 3> DCM_t2i = CalcDCM(main_direction_i, sub_direction_i); // Calc DCM Target->body - Matrix<3, 3> DCM_t2b = CalcDCM(pointing_t_b_, pointing_sub_t_b_); + Matrix<3, 3> DCM_t2b = CalcDCM(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body Matrix<3, 3> DCM_i2b = DCM_t2b * transpose(DCM_t2i); // Convert to Quaternion @@ -146,14 +146,14 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { if (previous_calc_time_s_ > 0.0) { double time_diff_sec = current_time_s - previous_calc_time_s_; - libra::Quaternion prev_q_b2i = prev_quaternion_i2b_.conjugate(); + libra::Quaternion prev_q_b2i = previous_quaternion_i2b_.conjugate(); libra::Quaternion q_diff = prev_q_b2i * quaternion_i2b_; q_diff = (2.0 / time_diff_sec) * q_diff; libra::Vector<3> angular_acc_b_rad_s2_; for (int i = 0; i < 3; i++) { angular_velocity_b_rad_s_[i] = q_diff[i]; - angular_acc_b_rad_s2_[i] = (prev_omega_b_rad_s_[i] - angular_velocity_b_rad_s_[i]) / time_diff_sec; + angular_acc_b_rad_s2_[i] = (previous_omega_b_rad_s_[i] - angular_velocity_b_rad_s_[i]) / time_diff_sec; } controlled_torque_b_Nm = inv_inertia_tensor_ * angular_acc_b_rad_s2_; } else { @@ -164,6 +164,6 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { AddTorque_b_Nm(controlled_torque_b_Nm); // save previous values previous_calc_time_s_ = current_time_s; - prev_quaternion_i2b_ = quaternion_i2b_; - prev_omega_b_rad_s_ = angular_velocity_b_rad_s_; + previous_quaternion_i2b_ = quaternion_i2b_; + previous_omega_b_rad_s_ = angular_velocity_b_rad_s_; } diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 04bd7a6f7..e253703a5 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -45,16 +45,17 @@ class ControlledAttitude : public Attitude { * @param [in] main_mode: Main control mode * @param [in] sub_mode: Sub control mode * @param [in] quaternion_i2b: Quaternion for INERTIAL_STABILIZE mode - * @param [in] pointing_t_b: Main target direction on the body fixed frame - * @param [in] pointing_sub_t_b: Sun target direction on the body fixed frame + * @param [in] main_target_direction_b: Main target direction on the body fixed frame + * @param [in] sub_target_direction_b: Sun target direction on the body fixed frame * @param [in] inertia_tensor_kgm2: Inertia tensor of the spacecraft [kg m^2] - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information * @param [in] orbit: Orbit * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, const Vector<3> pointing_t_b, - const Vector<3> pointing_sub_t_b, const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celes_info, - const Orbit* orbit, const std::string& simulation_object_name = "Attitude"); + ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, + const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, const Matrix<3, 3>& inertia_tensor_kgm2, + const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, + const std::string& simulation_object_name = "Attitude"); /** * @fn ~ControlledAttitude * @brief Destructor @@ -81,12 +82,12 @@ class ControlledAttitude : public Attitude { * @fn SetPointingTb * @brief Set main target direction on the body fixed frame */ - inline void SetPointingTb(Vector<3> pointing_t_b) { pointing_t_b_ = pointing_t_b; } + inline void SetPointingTb(Vector<3> main_target_direction_b) { main_target_direction_b_ = main_target_direction_b; } /** * @fn SetPointingSubTb * @brief Set sub target direction on the body fixed frame */ - inline void SetPointingSubTb(Vector<3> pointing_sub_t_b) { pointing_sub_t_b_ = pointing_sub_t_b; } + inline void SetPointingSubTb(Vector<3> sub_target_direction_b) { sub_target_direction_b_ = sub_target_direction_b; } /** * @fn Propagate @@ -96,17 +97,17 @@ class ControlledAttitude : public Attitude { virtual void Propagate(const double end_time_s); private: - AttCtrlMode main_mode_; //!< Main control mode - AttCtrlMode sub_mode_; //!< Sub control mode - libra::Vector<3> pointing_t_b_; //!< Main target direction on the body fixed frame - libra::Vector<3> pointing_sub_t_b_; //!< Sub target direction on tge body fixed frame - double previous_calc_time_s_ = -1.0; //!< Previous time of velocity calculation [sec] - libra::Quaternion prev_quaternion_i2b_; //!< Previous quaternion - libra::Vector<3> prev_omega_b_rad_s_; //!< Previous angular velocity [rad/s] + AttCtrlMode main_mode_; //!< Main control mode + AttCtrlMode sub_mode_; //!< Sub control mode + libra::Vector<3> main_target_direction_b_; //!< Main target direction on the body fixed frame + libra::Vector<3> sub_target_direction_b_; //!< Sub target direction on tge body fixed frame + double previous_calc_time_s_ = -1.0; //!< Previous time of velocity calculation [sec] + libra::Quaternion previous_quaternion_i2b_; //!< Previous quaternion + libra::Vector<3> previous_omega_b_rad_s_; //!< Previous angular velocity [rad/s] // Inputs - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information - const Orbit* orbit_; //!< Orbit information + const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information + const Orbit* orbit_; //!< Orbit information // Local functions /** @@ -137,7 +138,7 @@ class ControlledAttitude : public Attitude { * @fn CalcDCM * @brief Calculate direction cosine matrix with tow direction vectors * @param [in] main_direction: Main target direction - * @param [in] main_direction: Sub target direction + * @param [in] sub_direction: Sub target direction */ Matrix<3, 3> CalcDCM(const Vector<3> main_direction, const Vector<3> sub_direction); }; diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 6448d27d9..38d7fcf3e 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -36,11 +36,11 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel AttCtrlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); Quaternion quaternion_i2b; ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); - Vector<3> pointing_t_b, pointing_sub_t_b; - ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", pointing_t_b); - ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", pointing_sub_t_b); - attitude = - new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, pointing_t_b, pointing_sub_t_b, inertia_tensor, celes_info, orbit, mc_name); + Vector<3> main_target_direction_b, sub_target_direction_b; + ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); + ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); + attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor, + celes_info, orbit, mc_name); } else { std::cerr << "ERROR: attitude propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The attitude mode is automatically set as RK4" << std::endl; From 710935acbfe3d4bf880ce416668c0ea34d35c9fd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 18:58:52 +0100 Subject: [PATCH 0583/1086] Fix public function --- src/dynamics/attitude/controlled_attitude.cpp | 16 +++++------ src/dynamics/attitude/controlled_attitude.hpp | 27 ++++++++++--------- 2 files changed, 22 insertions(+), 21 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 8a692799a..a139b9949 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -69,17 +69,17 @@ void ControlledAttitude::Propagate(const double end_time_s) { } // Calc main target direction - main_direction_i = CalcTargetDirection(main_mode_); + main_direction_i = CalcTargetDirection_i(main_mode_); // Calc sub target direction - sub_direction_i = CalcTargetDirection(sub_mode_); + sub_direction_i = CalcTargetDirection_i(sub_mode_); // Calc attitude - PointingCtrl(main_direction_i, sub_direction_i); + PointingControl(main_direction_i, sub_direction_i); // Calc angular velocity CalcAngularVelocity(end_time_s); return; } -Vector<3> ControlledAttitude::CalcTargetDirection(AttCtrlMode mode) { +Vector<3> ControlledAttitude::CalcTargetDirection_i(AttCtrlMode mode) { Vector<3> direction; if (mode == SUN_POINTING) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); @@ -94,18 +94,18 @@ Vector<3> ControlledAttitude::CalcTargetDirection(AttCtrlMode mode) { return direction; } -void ControlledAttitude::PointingCtrl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i) { +void ControlledAttitude::PointingControl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i) { // Calc DCM ECI->Target - Matrix<3, 3> DCM_t2i = CalcDCM(main_direction_i, sub_direction_i); + Matrix<3, 3> DCM_t2i = CalcDcm(main_direction_i, sub_direction_i); // Calc DCM Target->body - Matrix<3, 3> DCM_t2b = CalcDCM(main_target_direction_b_, sub_target_direction_b_); + Matrix<3, 3> DCM_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body Matrix<3, 3> DCM_i2b = DCM_t2b * transpose(DCM_t2i); // Convert to Quaternion quaternion_i2b_ = Quaternion::fromDCM(DCM_i2b); } -Matrix<3, 3> ControlledAttitude::CalcDCM(const Vector<3> main_direction, const Vector<3> sub_direction) { +Matrix<3, 3> ControlledAttitude::CalcDcm(const Vector<3> main_direction, const Vector<3> sub_direction) { // Calc basis vectors Vector<3> ex, ey, ez; ex = main_direction; diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index e253703a5..b7276ac22 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -74,20 +74,20 @@ class ControlledAttitude : public Attitude { */ inline void SetSubMode(const AttCtrlMode sub_mode) { sub_mode_ = sub_mode; } /** - * @fn SetQuaternionI2T + * @fn SetQuaternion_i2t * @brief Set quaternion for INERTIAL_STABILIZE mode */ - inline void SetQuaternionI2T(const Quaternion quaternion_i2t) { quaternion_i2b_ = quaternion_i2t; } + inline void SetQuaternion_i2t(const Quaternion quaternion_i2t) { quaternion_i2b_ = quaternion_i2t; } /** - * @fn SetPointingTb + * @fn SetMainTargetDirection_b * @brief Set main target direction on the body fixed frame */ - inline void SetPointingTb(Vector<3> main_target_direction_b) { main_target_direction_b_ = main_target_direction_b; } + inline void SetMainTargetDirection_b(Vector<3> main_target_direction_b) { main_target_direction_b_ = main_target_direction_b; } /** - * @fn SetPointingSubTb + * @fn SetSubTargetDirection_b * @brief Set sub target direction on the body fixed frame */ - inline void SetPointingSubTb(Vector<3> sub_target_direction_b) { sub_target_direction_b_ = sub_target_direction_b; } + inline void SetSubTargetDirection_b(Vector<3> sub_target_direction_b) { sub_target_direction_b_ = sub_target_direction_b; } /** * @fn Propagate @@ -116,18 +116,19 @@ class ControlledAttitude : public Attitude { */ void Initialize(void); /** - * @fn CalcTargetDirection + * @fn CalcTargetDirection_i * @brief Calculate target direction from attitude control mode * @param [in] mode: Attitude control mode + * @return Target direction at the inertia frame0 */ - Vector<3> CalcTargetDirection(AttCtrlMode mode); + Vector<3> CalcTargetDirection_i(AttCtrlMode mode); /** - * @fn PointingCtrl + * @fn PointingControl * @brief Calculate attitude quaternion * @param [in] main_direction_i: Main target direction in the inertial frame - * @param [in] main_direction_i: Sub target direction in the inertial frame + * @param [in] sub_direction_i: Sub target direction in the inertial frame */ - void PointingCtrl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i); + void PointingControl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i); /** * @fn CalcAngularVelocity * @brief Calculate angular velocity @@ -135,12 +136,12 @@ class ControlledAttitude : public Attitude { */ void CalcAngularVelocity(const double current_time_s); /** - * @fn CalcDCM + * @fn CalcDcm * @brief Calculate direction cosine matrix with tow direction vectors * @param [in] main_direction: Main target direction * @param [in] sub_direction: Sub target direction */ - Matrix<3, 3> CalcDCM(const Vector<3> main_direction, const Vector<3> sub_direction); + Matrix<3, 3> CalcDcm(const Vector<3> main_direction, const Vector<3> sub_direction); }; #endif // S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ From f306995fb0ba5475a413d70164104387882811ca Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:02:15 +0100 Subject: [PATCH 0584/1086] Fix local function variables --- src/dynamics/attitude/controlled_attitude.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index a139b9949..c4da1f796 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -96,13 +96,13 @@ Vector<3> ControlledAttitude::CalcTargetDirection_i(AttCtrlMode mode) { void ControlledAttitude::PointingControl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i) { // Calc DCM ECI->Target - Matrix<3, 3> DCM_t2i = CalcDcm(main_direction_i, sub_direction_i); + Matrix<3, 3> dcm_t2i = CalcDcm(main_direction_i, sub_direction_i); // Calc DCM Target->body - Matrix<3, 3> DCM_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); + Matrix<3, 3> dcm_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body - Matrix<3, 3> DCM_i2b = DCM_t2b * transpose(DCM_t2i); + Matrix<3, 3> dcm_i2b = dcm_t2b * transpose(dcm_t2i); // Convert to Quaternion - quaternion_i2b_ = Quaternion::fromDCM(DCM_i2b); + quaternion_i2b_ = Quaternion::fromDCM(dcm_i2b); } Matrix<3, 3> ControlledAttitude::CalcDcm(const Vector<3> main_direction, const Vector<3> sub_direction) { @@ -116,13 +116,13 @@ Matrix<3, 3> ControlledAttitude::CalcDcm(const Vector<3> main_direction, const V ez = normalize(tmp3); // Generate DCM - Matrix<3, 3> DCM_; + Matrix<3, 3> dcm; for (int i = 0; i < 3; i++) { - DCM_[i][0] = ex[i]; - DCM_[i][1] = ey[i]; - DCM_[i][2] = ez[i]; + dcm[i][0] = ex[i]; + dcm[i][1] = ey[i]; + dcm[i][2] = ez[i]; } - return DCM_; + return dcm; } AttCtrlMode ConvertStringToCtrlMode(const std::string mode) { From 7981b2572775dfafaaa914b9e5f9bcb8d0b767b0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:03:12 +0100 Subject: [PATCH 0585/1086] Fix enum name --- src/dynamics/attitude/controlled_attitude.cpp | 6 +++--- src/dynamics/attitude/controlled_attitude.hpp | 20 +++++++++---------- src/dynamics/attitude/initialize_attitude.cpp | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index c4da1f796..d63519b16 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -12,7 +12,7 @@ using namespace std; #define THRESHOLD_CA cos(30.0 / 180.0 * libra::pi) // fix me -ControlledAttitude::ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, +ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const Quaternion quaternion_i2b, const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, const std::string& simulation_object_name) @@ -79,7 +79,7 @@ void ControlledAttitude::Propagate(const double end_time_s) { return; } -Vector<3> ControlledAttitude::CalcTargetDirection_i(AttCtrlMode mode) { +Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { Vector<3> direction; if (mode == SUN_POINTING) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); @@ -125,7 +125,7 @@ Matrix<3, 3> ControlledAttitude::CalcDcm(const Vector<3> main_direction, const V return dcm; } -AttCtrlMode ConvertStringToCtrlMode(const std::string mode) { +AttitudeControlMode ConvertStringToCtrlMode(const std::string mode) { if (mode == "INERTIAL_STABILIZE") { return INERTIAL_STABILIZE; } else if (mode == "SUN_POINTING") { diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index b7276ac22..934bbad12 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -13,10 +13,10 @@ #include "attitude.hpp" /** - * @enum AttCtrlMode + * @enum AttitudeControlMode * @brief Attitude control mode */ -enum AttCtrlMode { +enum AttitudeControlMode { INERTIAL_STABILIZE, //!< Inertial stabilize SUN_POINTING, //!< Sun pointing EARTH_CENTER_POINTING, //!< Earth center pointing @@ -27,11 +27,11 @@ enum AttCtrlMode { /** * @fn ConvertStringToCtrlMode - * @brief Convert string to AttCtrlMode + * @brief Convert string to AttitudeControlMode * @param [in] mode: Control mode in string * @return Attitude control mode */ -AttCtrlMode ConvertStringToCtrlMode(const std::string mode); +AttitudeControlMode ConvertStringToCtrlMode(const std::string mode); /** * @class ControlledAttitude @@ -52,7 +52,7 @@ class ControlledAttitude : public Attitude { * @param [in] orbit: Orbit * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - ControlledAttitude(const AttCtrlMode main_mode, const AttCtrlMode sub_mode, const Quaternion quaternion_i2b, + ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const Quaternion quaternion_i2b, const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, const std::string& simulation_object_name = "Attitude"); @@ -67,12 +67,12 @@ class ControlledAttitude : public Attitude { * @fn SetMainMode * @brief Set main control mode */ - inline void SetMainMode(const AttCtrlMode main_mode) { main_mode_ = main_mode; } + inline void SetMainMode(const AttitudeControlMode main_mode) { main_mode_ = main_mode; } /** * @fn SetSubMode * @brief Set sub control mode */ - inline void SetSubMode(const AttCtrlMode sub_mode) { sub_mode_ = sub_mode; } + inline void SetSubMode(const AttitudeControlMode sub_mode) { sub_mode_ = sub_mode; } /** * @fn SetQuaternion_i2t * @brief Set quaternion for INERTIAL_STABILIZE mode @@ -97,8 +97,8 @@ class ControlledAttitude : public Attitude { virtual void Propagate(const double end_time_s); private: - AttCtrlMode main_mode_; //!< Main control mode - AttCtrlMode sub_mode_; //!< Sub control mode + AttitudeControlMode main_mode_; //!< Main control mode + AttitudeControlMode sub_mode_; //!< Sub control mode libra::Vector<3> main_target_direction_b_; //!< Main target direction on the body fixed frame libra::Vector<3> sub_target_direction_b_; //!< Sub target direction on tge body fixed frame double previous_calc_time_s_ = -1.0; //!< Previous time of velocity calculation [sec] @@ -121,7 +121,7 @@ class ControlledAttitude : public Attitude { * @param [in] mode: Attitude control mode * @return Target direction at the inertia frame0 */ - Vector<3> CalcTargetDirection_i(AttCtrlMode mode); + Vector<3> CalcTargetDirection_i(AttitudeControlMode mode); /** * @fn PointingControl * @brief Calculate attitude quaternion diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 38d7fcf3e..65237243d 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -32,8 +32,8 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel const std::string main_mode_in = ini_file.ReadString(section_ca_, "main_mode"); const std::string sub_mode_in = ini_file.ReadString(section_ca_, "sub_mode"); - AttCtrlMode main_mode = ConvertStringToCtrlMode(main_mode_in); - AttCtrlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); + AttitudeControlMode main_mode = ConvertStringToCtrlMode(main_mode_in); + AttitudeControlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); Quaternion quaternion_i2b; ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); Vector<3> main_target_direction_b, sub_target_direction_b; From c60dba913d729d960ce182b1276377097408cea8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:08:15 +0100 Subject: [PATCH 0586/1086] Fix local function internal variable name --- src/dynamics/attitude/attitude_rk4.cpp | 35 +++++++++--------- src/dynamics/attitude/controlled_attitude.cpp | 37 +++++++++---------- 2 files changed, 35 insertions(+), 37 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 465019404..51b34f5df 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -4,15 +4,14 @@ */ #include "attitude_rk4.hpp" +#include #include #include -using namespace std; - -#include #include -AttitudeRk4::AttitudeRk4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, - const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name) +AttitudeRk4::AttitudeRk4(const libra::Vector<3>& angular_velocity_b_rad_s, const libra::Quaternion& quaternion_i2b, + const libra::Matrix<3, 3>& inertia_tensor_kgm2, const libra::Vector<3>& torque_b_Nm, const double propagation_step_s, + const std::string& simulation_object_name) : Attitude(simulation_object_name) { angular_velocity_b_rad_s_ = angular_velocity_b_rad_s; quaternion_i2b_ = quaternion_i2b; @@ -34,7 +33,7 @@ void AttitudeRk4::SetParameters(const MCSimExecutor& mc_simulator) { // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); - angular_momentum_reaction_wheel_b_Nms_ = Vector<3>(0.0); //!< Consider how to handle this variable + angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); //!< Consider how to handle this variable CalcAngularMomentum(); } @@ -50,8 +49,8 @@ void AttitudeRk4::Propagate(const double end_time_s) { CalcAngularMomentum(); } -Matrix<4, 4> AttitudeRk4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s) { - Matrix<4, 4> angular_velocity_matrix; +libra::Matrix<4, 4> AttitudeRk4::CalcAngularVelocityMatrix(libra::Vector<3> angular_velocity_b_rad_s) { + libra::Matrix<4, 4> angular_velocity_matrix; angular_velocity_matrix[0][0] = 0.0f; angular_velocity_matrix[0][1] = angular_velocity_b_rad_s[2]; @@ -73,28 +72,28 @@ Matrix<4, 4> AttitudeRk4::CalcAngularVelocityMatrix(Vector<3> angular_velocity_b return angular_velocity_matrix; } -Vector<7> AttitudeRk4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { +libra::Vector<7> AttitudeRk4::AttitudeDynamicsAndKinematics(libra::Vector<7> x, double t) { UNUSED(t); - Vector<7> dxdt; + libra::Vector<7> dxdt; - Vector<3> omega_b; + libra::Vector<3> omega_b; for (int i = 0; i < 3; i++) { omega_b[i] = x[i]; } angular_momentum_total_b_Nms_ = (inertia_tensor_kgm2_ * omega_b) + angular_momentum_reaction_wheel_b_Nms_; - Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::outer_product(omega_b, angular_momentum_total_b_Nms_)); + libra::Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::outer_product(omega_b, angular_momentum_total_b_Nms_)); for (int i = 0; i < 3; ++i) { dxdt[i] = rhs[i]; } - Vector<4> quaternion_i2b; + libra::Vector<4> quaternion_i2b; for (int i = 0; i < 4; i++) { quaternion_i2b[i] = x[i + 3]; } - Vector<4> d_quaternion = 0.5 * CalcAngularVelocityMatrix(omega_b) * quaternion_i2b; + libra::Vector<4> d_quaternion = 0.5 * CalcAngularVelocityMatrix(omega_b) * quaternion_i2b; for (int i = 0; i < 4; i++) { dxdt[i + 3] = d_quaternion[i]; @@ -104,7 +103,7 @@ Vector<7> AttitudeRk4::AttitudeDynamicsAndKinematics(Vector<7> x, double t) { } void AttitudeRk4::RungeKuttaOneStep(double t, double dt) { - Vector<7> x; + libra::Vector<7> x; for (int i = 0; i < 3; i++) { x[i] = angular_velocity_b_rad_s_[i]; } @@ -112,8 +111,8 @@ void AttitudeRk4::RungeKuttaOneStep(double t, double dt) { x[i + 3] = quaternion_i2b_[i]; } - Vector<7> k1, k2, k3, k4; - Vector<7> xk2, xk3, xk4; + libra::Vector<7> k1, k2, k3, k4; + libra::Vector<7> xk2, xk3, xk4; k1 = AttitudeDynamicsAndKinematics(x, t); xk2 = x + (dt / 2.0) * k1; @@ -126,7 +125,7 @@ void AttitudeRk4::RungeKuttaOneStep(double t, double dt) { k4 = AttitudeDynamicsAndKinematics(xk4, (t + dt)); - Vector<7> next_x = x + (dt / 6.0) * (k1 + 2.0 * k2 + 2.0 * k3 + k4); + libra::Vector<7> next_x = x + (dt / 6.0) * (k1 + 2.0 * k2 + 2.0 * k3 + k4); for (int i = 0; i < 3; i++) { angular_velocity_b_rad_s_[i] = next_x[i]; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index d63519b16..eeae34e91 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -8,14 +8,13 @@ #include #include -using namespace std; +#define THRESHOLD_CA cos(30.0 / 180.0 * libra::pi) // FIXME -#define THRESHOLD_CA cos(30.0 / 180.0 * libra::pi) // fix me - -ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const Quaternion quaternion_i2b, - const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, - const Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, - const Orbit* orbit, const std::string& simulation_object_name) +ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, + const libra::Quaternion quaternion_i2b, const libra::Vector<3> main_target_direction_b, + const libra::Vector<3> sub_target_direction_b, const libra::Matrix<3, 3>& inertia_tensor_kgm2, + const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, + const std::string& simulation_object_name) : Attitude(simulation_object_name), main_mode_(main_mode), sub_mode_(sub_mode), @@ -41,7 +40,7 @@ void ControlledAttitude::Initialize(void) { { // sub mode check if (main_mode_ == sub_mode_) { - cout << "sub mode should not equal to main mode. \n"; + std::cout << "sub mode should not equal to main mode. \n"; is_calc_enabled_ = false; return; } @@ -51,7 +50,7 @@ void ControlledAttitude::Initialize(void) { double tmp = inner_product(main_target_direction_b_, sub_target_direction_b_); tmp = std::abs(tmp); if (tmp > THRESHOLD_CA) { - cout << "sub target direction should separate from the main target direction. \n"; + std::cout << "sub target direction should separate from the main target direction. \n"; is_calc_enabled_ = false; return; } @@ -94,29 +93,29 @@ Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { return direction; } -void ControlledAttitude::PointingControl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i) { +void ControlledAttitude::PointingControl(const libra::Vector<3> main_direction_i, const libra::Vector<3> sub_direction_i) { // Calc DCM ECI->Target - Matrix<3, 3> dcm_t2i = CalcDcm(main_direction_i, sub_direction_i); + libra::Matrix<3, 3> dcm_t2i = CalcDcm(main_direction_i, sub_direction_i); // Calc DCM Target->body - Matrix<3, 3> dcm_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); + libra::Matrix<3, 3> dcm_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body - Matrix<3, 3> dcm_i2b = dcm_t2b * transpose(dcm_t2i); + libra::Matrix<3, 3> dcm_i2b = dcm_t2b * transpose(dcm_t2i); // Convert to Quaternion quaternion_i2b_ = Quaternion::fromDCM(dcm_i2b); } -Matrix<3, 3> ControlledAttitude::CalcDcm(const Vector<3> main_direction, const Vector<3> sub_direction) { +libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_direction, const libra::Vector<3> sub_direction) { // Calc basis vectors - Vector<3> ex, ey, ez; + libra::Vector<3> ex, ey, ez; ex = main_direction; - Vector<3> tmp1 = outer_product(ex, sub_direction); - Vector<3> tmp2 = outer_product(tmp1, ex); + libra::Vector<3> tmp1 = outer_product(ex, sub_direction); + libra::Vector<3> tmp2 = outer_product(tmp1, ex); ey = normalize(tmp2); - Vector<3> tmp3 = outer_product(ex, ey); + libra::Vector<3> tmp3 = outer_product(ex, ey); ez = normalize(tmp3); // Generate DCM - Matrix<3, 3> dcm; + libra::Matrix<3, 3> dcm; for (int i = 0; i < 3; i++) { dcm[i][0] = ex[i]; dcm[i][1] = ey[i]; From a1d70e565e5e34511f34dd1c570b78858af64ec1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:11:23 +0100 Subject: [PATCH 0587/1086] Fix function arguments --- src/dynamics/attitude/initialize_attitude.cpp | 14 +++++++------- src/dynamics/attitude/initialize_attitude.hpp | 12 ++++++------ 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 65237243d..1ecd982d6 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -6,11 +6,11 @@ #include -Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, - const Matrix<3, 3> inertia_tensor, const int sat_id) { +Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* local_celestial_information, + const double step_width_s, const Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id) { IniAccess ini_file(file_name); const char* section_ = "ATTITUDE"; - std::string mc_name = section_ + std::to_string(sat_id); // FIXME + std::string mc_name = section_ + std::to_string(spacecraft_id); // FIXME Attitude* attitude; const std::string propagate_mode = ini_file.ReadString(section_, "propagate_mode"); @@ -24,7 +24,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); - attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); } else if (propagate_mode == "CONTROLLED") { // Controlled attitude IniAccess ini_file_ca(file_name); @@ -39,8 +39,8 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel Vector<3> main_target_direction_b, sub_target_direction_b; ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); - attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor, - celes_info, orbit, mc_name); + attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor_kgm2, + local_celestial_information, orbit, mc_name); } else { std::cerr << "ERROR: attitude propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The attitude mode is automatically set as RK4" << std::endl; @@ -52,7 +52,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); - attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor, torque_b, step_sec, mc_name); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); } return attitude; diff --git a/src/dynamics/attitude/initialize_attitude.hpp b/src/dynamics/attitude/initialize_attitude.hpp index dbe34e786..123e55a98 100644 --- a/src/dynamics/attitude/initialize_attitude.hpp +++ b/src/dynamics/attitude/initialize_attitude.hpp @@ -15,12 +15,12 @@ * @brief Initialize function for Attitude * @param [in] file_name: Path to the initialize file * @param [in] orbit: Orbit information - * @param [in] celes_info: Celestial information - * @param [in] step_sec: Step width [sec] - * @param [in] inertia_tensor: Inertia tensor [kg m^2] - * @param [in] sat_id: Satellite ID + * @param [in] local_celestial_information: Celestial information + * @param [in] step_width_s: Step width [sec] + * @param [in] inertia_tensor_kgm2: Inertia tensor [kg m^2] + * @param [in] spacecraft_id: Satellite ID */ -Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* celes_info, const double step_sec, - const Matrix<3, 3> inertia_tensor, const int sat_id); +Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* local_celestial_information, + const double step_width_s, const Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id); #endif // S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_HPP_ From ffcedb33f4778d9547a61b5924128c44a2414d9f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:15:09 +0100 Subject: [PATCH 0588/1086] Remove using --- src/dynamics/orbit/orbit.cpp | 24 +++++++-------- src/dynamics/orbit/orbit.hpp | 57 ++++++++++++++++-------------------- 2 files changed, 38 insertions(+), 43 deletions(-) diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 8f4f93ae6..f47681076 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -5,14 +5,14 @@ #include "orbit.hpp" Quaternion Orbit::CalcQuaternionI2LVLH() const { - Vector<3> lvlh_x = sat_position_i_; // x-axis in LVLH frame is position vector direction from geocenter to satellite - Vector<3> lvlh_ex = normalize(lvlh_x); - Vector<3> lvlh_z = outer_product(sat_position_i_, sat_velocity_i_); // z-axis in LVLH frame is angular momentum vector direction of orbit - Vector<3> lvlh_ez = normalize(lvlh_z); - Vector<3> lvlh_y = outer_product(lvlh_z, lvlh_x); - Vector<3> lvlh_ey = normalize(lvlh_y); + libra::Vector<3> lvlh_x = sat_position_i_; // x-axis in LVLH frame is position vector direction from geocenter to satellite + libra::Vector<3> lvlh_ex = normalize(lvlh_x); + libra::Vector<3> lvlh_z = outer_product(sat_position_i_, sat_velocity_i_); // z-axis in LVLH frame is angular momentum vector direction of orbit + libra::Vector<3> lvlh_ez = normalize(lvlh_z); + libra::Vector<3> lvlh_y = outer_product(lvlh_z, lvlh_x); + libra::Vector<3> lvlh_ey = normalize(lvlh_y); - Matrix<3, 3> dcm_i2lvlh; + libra::Matrix<3, 3> dcm_i2lvlh; dcm_i2lvlh[0][0] = lvlh_ex[0]; dcm_i2lvlh[0][1] = lvlh_ex[1]; dcm_i2lvlh[0][2] = lvlh_ex[2]; @@ -23,19 +23,19 @@ Quaternion Orbit::CalcQuaternionI2LVLH() const { dcm_i2lvlh[2][1] = lvlh_ez[1]; dcm_i2lvlh[2][2] = lvlh_ez[2]; - Quaternion q_i2lvlh = Quaternion::fromDCM(dcm_i2lvlh); + libra::Quaternion q_i2lvlh = Quaternion::fromDCM(dcm_i2lvlh); return q_i2lvlh.normalize(); } void Orbit::TransEciToEcef(void) { - Matrix<3, 3> dcm_i_to_xcxf = celes_info_->GetEarthRotation().GetDcmJ2000ToXcxf(); + libra::Matrix<3, 3> dcm_i_to_xcxf = celes_info_->GetEarthRotation().GetDcmJ2000ToXcxf(); sat_position_ecef_ = dcm_i_to_xcxf * sat_position_i_; // convert velocity vector in ECI to the vector in ECEF - Vector<3> OmegaE{0.0}; + libra::Vector<3> OmegaE{0.0}; OmegaE[2] = environment::earth_mean_angular_velocity_rad_s; - Vector<3> wExr = outer_product(OmegaE, sat_position_i_); - Vector<3> V_wExr = sat_velocity_i_ - wExr; + libra::Vector<3> wExr = outer_product(OmegaE, sat_position_i_); + libra::Vector<3> V_wExr = sat_velocity_i_ - wExr; sat_velocity_ecef_ = dcm_i_to_xcxf * V_wExr; } diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index c9c033424..d0fb22ff2 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -6,21 +6,16 @@ #ifndef S2E_DYNAMICS_ORBIT_ORBIT_HPP_ #define S2E_DYNAMICS_ORBIT_ORBIT_HPP_ +#include +#include +#include +#include #include #include #include #include #include -using libra::Matrix; -using libra::Quaternion; -using libra::Vector; - -#include -#include -#include -#include - /** * @enum OrbitPropagateMode * @brief Propagation mode of orbit @@ -74,7 +69,7 @@ class Orbit : public ILoggable { * @brief Update attitude information * @param [in] q_i2b: End time of simulation [sec] */ - inline void UpdateAtt(Quaternion q_i2b) { sat_velocity_b_ = q_i2b.frame_conv(sat_velocity_i_); } + inline void UpdateAtt(libra::Quaternion q_i2b) { sat_velocity_b_ = q_i2b.frame_conv(sat_velocity_i_); } /** * @fn AddPositionOffset @@ -82,7 +77,7 @@ class Orbit : public ILoggable { * @note Is this really needed? * @param [in] offset_i: Offset vector in the inertial frame [m] */ - inline virtual void AddPositionOffset(Vector<3> offset_i) { (void)offset_i; } + inline virtual void AddPositionOffset(libra::Vector<3> offset_i) { (void)offset_i; } // Getters /** @@ -99,27 +94,27 @@ class Orbit : public ILoggable { * @fn GetSatPosition_i * @brief Return spacecraft position in the inertial frame [m] */ - inline Vector<3> GetSatPosition_i() const { return sat_position_i_; } + inline libra::Vector<3> GetSatPosition_i() const { return sat_position_i_; } /** * @fn GetSatPosition_ecef * @brief Return spacecraft position in the ECEF frame [m] */ - inline Vector<3> GetSatPosition_ecef() const { return sat_position_ecef_; } + inline libra::Vector<3> GetSatPosition_ecef() const { return sat_position_ecef_; } /** * @fn GetSatVelocity_i * @brief Return spacecraft velocity in the inertial frame [m/s] */ - inline Vector<3> GetSatVelocity_i() const { return sat_velocity_i_; } + inline libra::Vector<3> GetSatVelocity_i() const { return sat_velocity_i_; } /** * @fn GetSatVelocity_b * @brief Return spacecraft velocity in the body fixed frame [m/s] */ - inline Vector<3> GetSatVelocity_b() const { return sat_velocity_b_; } + inline libra::Vector<3> GetSatVelocity_b() const { return sat_velocity_b_; } /** * @fn GetSatVelocity_ecef * @brief Return spacecraft velocity in the ECEF frame [m/s] */ - inline Vector<3> GetSatVelocity_ecef() const { return sat_velocity_ecef_; } + inline libra::Vector<3> GetSatVelocity_ecef() const { return sat_velocity_ecef_; } /** * @fn GetGeodeticPosition * @brief Return spacecraft position in the geodetic frame [m] @@ -130,8 +125,8 @@ class Orbit : public ILoggable { inline double GetLat_rad() const { return sat_position_geo_.GetLat_rad(); } inline double GetLon_rad() const { return sat_position_geo_.GetLon_rad(); } inline double GetAlt_m() const { return sat_position_geo_.GetAlt_m(); } - inline Vector<3> GetLatLonAlt() const { - Vector<3> vec; + inline libra::Vector<3> GetLatLonAlt() const { + libra::Vector<3> vec; vec(0) = sat_position_geo_.GetLat_rad(); vec(1) = sat_position_geo_.GetLon_rad(); vec(2) = sat_position_geo_.GetAlt_m(); @@ -148,14 +143,14 @@ class Orbit : public ILoggable { * @fn SetAcceleration_i * @brief Set acceleration in the inertial frame [m/s2] */ - inline void SetAcceleration_i(Vector<3> acceleration_i) { acc_i_ = acceleration_i; } + inline void SetAcceleration_i(libra::Vector<3> acceleration_i) { acc_i_ = acceleration_i; } /** * @fn AddForce_i * @brief Add force * @param [in] force_i: Force in the inertial frame [N] * @param [in] spacecraft_mass: Mass of spacecraft [kg] */ - inline void AddForce_i(Vector<3> force_i, double spacecraft_mass) { + inline void AddForce_i(libra::Vector<3> force_i, double spacecraft_mass) { force_i /= spacecraft_mass; acc_i_ += force_i; } @@ -163,7 +158,7 @@ class Orbit : public ILoggable { * @fn AddAcceleration_i_m_s2 * @brief Add acceleration in the inertial frame [m/s2] */ - inline void AddAcceleration_i_m_s2(Vector<3> acceleration_i) { acc_i_ += acceleration_i; } + inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i) { acc_i_ += acceleration_i; } /** * @fn AddForce_i * @brief Add force @@ -171,7 +166,7 @@ class Orbit : public ILoggable { * @param [in] q_i2b: Quaternion from the inertial frame to the body fixed frame * @param [in] spacecraft_mass: Mass of spacecraft [kg] */ - inline void AddForce_b_N(Vector<3> force_b, Quaternion q_i2b, double spacecraft_mass) { + inline void AddForce_b_N(libra::Vector<3> force_b, libra::Quaternion q_i2b, double spacecraft_mass) { auto force_i = q_i2b.frame_conv_inv(force_b); AddForce_i(force_i, spacecraft_mass); } @@ -180,7 +175,7 @@ class Orbit : public ILoggable { * @fn CalcQuaternionI2LVLH * @brief Calculate quaternion from the inertial frame to the LVLH frame */ - Quaternion CalcQuaternionI2LVLH() const; + libra::Quaternion CalcQuaternionI2LVLH() const; // Override ILoggable /** @@ -201,16 +196,16 @@ class Orbit : public ILoggable { bool is_calc_enabled_ = false; //!< Calculate flag OrbitPropagateMode propagate_mode_; //!< Propagation mode - Vector<3> sat_position_i_; //!< Spacecraft position in the inertial frame [m] - Vector<3> sat_position_ecef_; //!< Spacecraft position in the ECEF frame [m] - GeodeticPosition sat_position_geo_; //!< Spacecraft position in the Geodetic frame + libra::Vector<3> sat_position_i_; //!< Spacecraft position in the inertial frame [m] + libra::Vector<3> sat_position_ecef_; //!< Spacecraft position in the ECEF frame [m] + GeodeticPosition sat_position_geo_; //!< Spacecraft position in the Geodetic frame - Vector<3> sat_velocity_i_; //!< Spacecraft velocity in the inertial frame [m/s] - Vector<3> sat_velocity_b_; //!< Spacecraft velocity in the body frame [m/s] - Vector<3> sat_velocity_ecef_; //!< Spacecraft velocity in the ECEF frame [m/s] + libra::Vector<3> sat_velocity_i_; //!< Spacecraft velocity in the inertial frame [m/s] + libra::Vector<3> sat_velocity_b_; //!< Spacecraft velocity in the body frame [m/s] + libra::Vector<3> sat_velocity_ecef_; //!< Spacecraft velocity in the ECEF frame [m/s] - Vector<3> acc_i_; //!< Spacecraft acceleration in the inertial frame [m/s2] - //!< NOTE: Clear to zero at the end of the Propagate function + libra::Vector<3> acc_i_; //!< Spacecraft acceleration in the inertial frame [m/s2] + //!< NOTE: Clear to zero at the end of the Propagate function // Frame Conversion TODO: consider other planet /** From 2289076b5746a4cab61c34ba3aca1caad96ab33d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:22:44 +0100 Subject: [PATCH 0589/1086] Fix private variable names --- src/dynamics/orbit/encke_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/encke_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/initialize_orbit.cpp | 14 +++++++------- src/dynamics/orbit/initialize_orbit.hpp | 4 ++-- src/dynamics/orbit/kepler_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/kepler_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/orbit.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 6 +++--- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/orbit/relative_orbit.hpp | 8 ++++---- src/dynamics/orbit/rk4_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 10 +++++----- 14 files changed, 38 insertions(+), 38 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index b1e8c6758..94f34cbd9 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -9,10 +9,10 @@ #include "../../library/orbit/orbital_elements.hpp" -EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celes_info, const double mu_m3_s2, const double prop_step_s, +EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, const double error_tolerance) - : Orbit(celes_info), libra::ODE<6>(prop_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), prop_step_s_(prop_step_s) { + : Orbit(celestial_information), libra::ODE<6>(prop_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), prop_step_s_(prop_step_s) { prop_time_s_ = 0.0; Initialize(current_jd, init_position_i_m, init_velocity_i_m_s); } diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 220e86f6d..8c1fd62ba 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -19,7 +19,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn EnckeOrbitPropagation * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] prop_step_s: Propagation step width [sec] * @param [in] current_jd: Current Julian day [day] @@ -27,7 +27,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] init_velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] * @param [in] error_tolerance: Error tolerance threshold */ - EnckeOrbitPropagation(const CelestialInformation* celes_info, const double mu_m3_s2, const double prop_step_s, const double current_jd, + EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, const double error_tolerance); /** * @fn ~EnckeOrbitPropagation diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index d11261ee6..f60e7f96a 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -12,7 +12,7 @@ #include "rk4_orbit_propagation.hpp" #include "sgp4_orbit_propagation.hpp" -Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section, RelativeInformation* rel_info) { auto conf = IniAccess(ini_path); const char* section_ = section.c_str(); @@ -33,7 +33,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celes_info, gravity_constant, stepSec, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant, stepSec, position_i_m, velocity_i_m_s); } else if (propagate_mode == "SGP4") { // Initialize SGP4 orbit propagator int wgs = conf.ReadInt(section_, "wgs"); @@ -41,7 +41,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d conf.ReadChar(section_, "tle1", 80, tle1); conf.ReadChar(section_, "tle2", 80, tle2); - orbit = new Sgp4OrbitPropagation(celes_info, tle1, tle2, wgs, current_jd); + orbit = new Sgp4OrbitPropagation(celestial_information, tle1, tle2, wgs, current_jd); } else if (propagate_mode == "RELATIVE") { // initialize orbit for relative dynamics of formation flying RelativeOrbit::RelativeOrbitUpdateMethod update_method = @@ -58,7 +58,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat int reference_sat_id = conf.ReadInt(section_, "reference_satellite_id"); - orbit = new RelativeOrbit(celes_info, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, init_relative_velocity_lvlh, + orbit = new RelativeOrbit(celestial_information, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, rel_info); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation @@ -83,7 +83,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d oe = OrbitalElements(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); } KeplerOrbit kepler_orbit(mu_m3_s2, oe); - orbit = new KeplerOrbitPropagation(celes_info, current_jd, kepler_orbit); + orbit = new KeplerOrbitPropagation(celestial_information, current_jd, kepler_orbit); } else if (propagate_mode == "ENCKE") { // initialize orbit for Encke's method Vector<3> position_i_m; @@ -95,7 +95,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d } double error_tolerance = conf.ReadDouble(section_, "error_tolerance"); - orbit = new EnckeOrbitPropagation(celes_info, gravity_constant, stepSec, current_jd, position_i_m, velocity_i_m_s, error_tolerance); + orbit = new EnckeOrbitPropagation(celestial_information, gravity_constant, stepSec, current_jd, position_i_m, velocity_i_m_s, error_tolerance); } else { std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; @@ -107,7 +107,7 @@ Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, d position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celes_info, gravity_constant, stepSec, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant, stepSec, position_i_m, velocity_i_m_s); } orbit->SetIsCalcEnabled(conf.ReadEnable(section_, "calculation")); diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index 3784dc8ad..4379d7ed9 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -15,7 +15,7 @@ class RelativeInformation; /** * @fn InitOrbit * @brief Initialize function for Orbit class - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] ini_path: Path to initialize file * @param [in] stepSec: Step width [sec] * @param [in] current_jd: Current Julian day [day] @@ -23,7 +23,7 @@ class RelativeInformation; * @param [in] section: Section name * @param [in] rel_info: Relative information */ -Orbit* InitOrbit(const CelestialInformation* celes_info, std::string ini_path, double stepSec, double current_jd, double gravity_constant, +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_jd, double gravity_constant, std::string section = "ORBIT", RelativeInformation* rel_info = (RelativeInformation*)nullptr); /** diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 5d37926a3..1afcd0e23 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -8,8 +8,8 @@ #include "../../library/math/s2e_math.hpp" -KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celes_info, const double current_jd, KeplerOrbit kepler_orbit) - : Orbit(celes_info), KeplerOrbit(kepler_orbit) { +KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_jd, KeplerOrbit kepler_orbit) + : Orbit(celestial_information), KeplerOrbit(kepler_orbit) { UpdateState(current_jd); } diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index bf790ebec..ad401128f 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -19,11 +19,11 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { /** * @fn KeplerOrbitPropagation * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] current_jd: Current Julian day [day] * @param [in] kepler_orbit: Kepler orbit */ - KeplerOrbitPropagation(const CelestialInformation* celes_info, const double current_jd, KeplerOrbit kepler_orbit); + KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_jd, KeplerOrbit kepler_orbit); /** * @fn ~KeplerOrbitPropagation * @brief Destructor diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index f47681076..444ab6e17 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -28,7 +28,7 @@ Quaternion Orbit::CalcQuaternionI2LVLH() const { } void Orbit::TransEciToEcef(void) { - libra::Matrix<3, 3> dcm_i_to_xcxf = celes_info_->GetEarthRotation().GetDcmJ2000ToXcxf(); + libra::Matrix<3, 3> dcm_i_to_xcxf = celestial_information_->GetEarthRotation().GetDcmJ2000ToXcxf(); sat_position_ecef_ = dcm_i_to_xcxf * sat_position_i_; // convert velocity vector in ECI to the vector in ECEF diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index d0fb22ff2..ed0789e33 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -47,9 +47,9 @@ class Orbit : public ILoggable { /** * @fn Orbit * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information */ - Orbit(const CelestialInformation* celes_info) : celes_info_(celes_info) {} + Orbit(const CelestialInformation* celestial_information) : celestial_information_(celestial_information) {} /** * @fn ~Orbit * @brief Destructor @@ -190,7 +190,7 @@ class Orbit : public ILoggable { virtual std::string GetLogValue() const; protected: - const CelestialInformation* celes_info_; //!< Celestial information + const CelestialInformation* celestial_information_; //!< Celestial information // Settings bool is_calc_enabled_ = false; //!< Calculate flag diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index ebd84b487..968ad1972 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -8,11 +8,11 @@ #include "rk4_orbit_propagation.hpp" -RelativeOrbit::RelativeOrbit(const CelestialInformation* celes_info, double mu, double timestep, int reference_sat_id, +RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu, double timestep, int reference_sat_id, Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info) - : Orbit(celes_info), + : Orbit(celestial_information), libra::ODE<6>(timestep), mu_(mu), reference_sat_id_(reference_sat_id), diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index ac07e0010..13db23084 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -28,7 +28,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { /** * @fn RelativeOrbit * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] timestep: Time step [sec] * @param [in] reference_sat_id: Reference satellite ID * @param [in] initial_relative_position_lvlh: Initial value of relative position at the LVLH frame of reference satellite @@ -38,9 +38,9 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] stm_model_type: State transition matrix type * @param [in] rel_info: Relative information */ - RelativeOrbit(const CelestialInformation* celes_info, double mu, double timestep, int reference_sat_id, Vector<3> initial_relative_position_lvlh, - Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, - STMModel stm_model_type, RelativeInformation* rel_info); + RelativeOrbit(const CelestialInformation* celestial_information, double mu, double timestep, int reference_sat_id, + Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, + RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info); /** * @fn ~RelativeOrbit * @brief Destructor diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 489de2b0a..7b3d03852 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -10,9 +10,9 @@ using std::string; -Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celes_info, double mu, double timestep, Vector<3> init_position, +Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu, double timestep, Vector<3> init_position, Vector<3> init_velocity, double init_time) - : Orbit(celes_info), ODE(timestep), mu(mu) { + : Orbit(celestial_information), ODE(timestep), mu(mu) { propagate_mode_ = OrbitPropagateMode::kRk4; prop_time_ = 0.0; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index c973da654..2ddbaaf9a 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -24,14 +24,14 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn Rk4OrbitPropagation * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] mu: Gravity constant [m3/s2] * @param [in] timestep: Step width [sec] * @param [in] init_position: Initial value of position in the inertial frame [m] * @param [in] init_velocity: Initial value of velocity in the inertial frame [m/s] * @param [in] init_time: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celes_info, double mu, double timestep, Vector<3> init_position, Vector<3> init_velocity, + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu, double timestep, Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); /** * @fn ~Rk4OrbitPropagation diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 10d20f9e9..cff8be535 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -10,8 +10,8 @@ #include using namespace std; -Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celes_info, char* tle1, char* tle2, int wgs, double current_jd) - : Orbit(celes_info) { +Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_jd) + : Orbit(celestial_information) { propagate_mode_ = OrbitPropagateMode::kSgp4; if (wgs == 0) { diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 823f69221..50181bfa8 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -22,13 +22,13 @@ class Sgp4OrbitPropagation : public Orbit { /** * @fn Sgp4OrbitPropagation * @brief Constructor - * @param [in] celes_info: Celestial information + * @param [in] celestial_information: Celestial information * @param [in] tle1: The first line of TLE * @param [in] tle2: The second line of TLE * @param [in] wgs: Wold Geodetic System * @param [in] current_jd: Current Julian day [day] */ - Sgp4OrbitPropagation(const CelestialInformation* celes_info, char* tle1, char* tle2, int wgs, double current_jd); + Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_jd); // Override Orbit /** @@ -47,9 +47,9 @@ class Sgp4OrbitPropagation : public Orbit { Vector<3> GetESIOmega(); private: - gravconsttype whichconst_; //!< Gravity constant value type - elsetrec satrec_; //!< Structure data for SGP4 library - const CelestialInformation* celes_info_; //!< Celestial information + gravconsttype whichconst_; //!< Gravity constant value type + elsetrec satrec_; //!< Structure data for SGP4 library + const CelestialInformation* celestial_information_; //!< Celestial information }; #endif // S2E_DYNAMICS_ORBIT_SGP4_ORBIT_PROPAGATION_HPP_ From bc655ea4743554734969cccdb0523a29b4848de4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:26:55 +0100 Subject: [PATCH 0590/1086] Fix private variable names --- .../orbit/encke_orbit_propagation.cpp | 16 +++---- .../orbit/kepler_orbit_propagation.cpp | 4 +- src/dynamics/orbit/orbit.cpp | 29 +++++------ src/dynamics/orbit/orbit.hpp | 48 +++++++++---------- src/dynamics/orbit/relative_orbit.cpp | 12 ++--- src/dynamics/orbit/rk4_orbit_propagation.cpp | 40 ++++++++-------- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 6 +-- 7 files changed, 78 insertions(+), 77 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 94f34cbd9..c97ebaa5a 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -24,10 +24,10 @@ void EnckeOrbitPropagation::Propagate(double endtime, double current_jd) { if (!is_calc_enabled_) return; // Rectification - double norm_sat_position_m = norm(sat_position_i_); + double norm_sat_position_m = norm(spacecraft_position_i_m_); double norm_diff_position_m = norm(diff_position_i_m_); if (norm_diff_position_m / norm_sat_position_m > error_tolerance_) { - Initialize(current_jd, sat_position_i_, sat_velocity_i_); + Initialize(current_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); } // Update reference orbit @@ -67,7 +67,7 @@ void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs double r_m = norm(ref_position_i_m_); double r_m3 = pow(r_m, 3.0); - diff_acc_i_m_s2 = -(mu_m3_s2_ / r_m3) * (q_func * sat_position_i_ + diff_pos_i_m) + acc_i_; + diff_acc_i_m_s2 = -(mu_m3_s2_ / r_m3) * (q_func * spacecraft_position_i_m_ + diff_pos_i_m) + spacecraft_acceleration_i_m_s2_; rhs[0] = state[3]; rhs[1] = state[4]; @@ -80,7 +80,7 @@ void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs // Private Functions void EnckeOrbitPropagation::Initialize(double current_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s) { // General - fill_up(acc_i_, 0.0); + fill_up(spacecraft_acceleration_i_m_s2_, 0.0); // reference orbit ref_position_i_m_ = init_ref_position_i_m; @@ -99,8 +99,8 @@ void EnckeOrbitPropagation::Initialize(double current_jd, Vector<3> init_ref_pos } void EnckeOrbitPropagation::UpdateSatOrbit() { - sat_position_i_ = ref_position_i_m_ + diff_position_i_m_; - sat_velocity_i_ = ref_velocity_i_m_s_ + diff_velocity_i_m_s_; + spacecraft_position_i_m_ = ref_position_i_m_ + diff_position_i_m_; + spacecraft_velocity_i_m_s_ = ref_velocity_i_m_s_ + diff_velocity_i_m_s_; TransEciToEcef(); TransEcefToGeo(); @@ -108,10 +108,10 @@ void EnckeOrbitPropagation::UpdateSatOrbit() { double EnckeOrbitPropagation::CalcQFunction(Vector<3> diff_pos_i) { double r2; - r2 = inner_product(sat_position_i_, sat_position_i_); + r2 = inner_product(spacecraft_position_i_m_, spacecraft_position_i_m_); Vector<3> dr_2r; - dr_2r = diff_pos_i - 2.0 * sat_position_i_; + dr_2r = diff_pos_i - 2.0 * spacecraft_position_i_m_; double q = inner_product(diff_pos_i, dr_2r) / r2; diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 1afcd0e23..2aedcaff4 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -26,8 +26,8 @@ void KeplerOrbitPropagation::Propagate(double endtime, double current_jd) { // Private Function void KeplerOrbitPropagation::UpdateState(const double current_jd) { CalcPosVel(current_jd); - sat_position_i_ = position_i_m_; - sat_velocity_i_ = velocity_i_m_s_; + spacecraft_position_i_m_ = position_i_m_; + spacecraft_velocity_i_m_s_ = velocity_i_m_s_; TransEciToEcef(); TransEcefToGeo(); } diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 444ab6e17..db05c0c7f 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -5,9 +5,10 @@ #include "orbit.hpp" Quaternion Orbit::CalcQuaternionI2LVLH() const { - libra::Vector<3> lvlh_x = sat_position_i_; // x-axis in LVLH frame is position vector direction from geocenter to satellite + libra::Vector<3> lvlh_x = spacecraft_position_i_m_; // x-axis in LVLH frame is position vector direction from geocenter to satellite libra::Vector<3> lvlh_ex = normalize(lvlh_x); - libra::Vector<3> lvlh_z = outer_product(sat_position_i_, sat_velocity_i_); // z-axis in LVLH frame is angular momentum vector direction of orbit + libra::Vector<3> lvlh_z = + outer_product(spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); // z-axis in LVLH frame is angular momentum vector direction of orbit libra::Vector<3> lvlh_ez = normalize(lvlh_z); libra::Vector<3> lvlh_y = outer_product(lvlh_z, lvlh_x); libra::Vector<3> lvlh_ey = normalize(lvlh_y); @@ -29,17 +30,17 @@ Quaternion Orbit::CalcQuaternionI2LVLH() const { void Orbit::TransEciToEcef(void) { libra::Matrix<3, 3> dcm_i_to_xcxf = celestial_information_->GetEarthRotation().GetDcmJ2000ToXcxf(); - sat_position_ecef_ = dcm_i_to_xcxf * sat_position_i_; + spacecraft_position_ecef_m_ = dcm_i_to_xcxf * spacecraft_position_i_m_; // convert velocity vector in ECI to the vector in ECEF libra::Vector<3> OmegaE{0.0}; OmegaE[2] = environment::earth_mean_angular_velocity_rad_s; - libra::Vector<3> wExr = outer_product(OmegaE, sat_position_i_); - libra::Vector<3> V_wExr = sat_velocity_i_ - wExr; - sat_velocity_ecef_ = dcm_i_to_xcxf * V_wExr; + libra::Vector<3> wExr = outer_product(OmegaE, spacecraft_position_i_m_); + libra::Vector<3> V_wExr = spacecraft_velocity_i_m_s_ - wExr; + spacecraft_velocity_ecef_m_s_ = dcm_i_to_xcxf * V_wExr; } -void Orbit::TransEcefToGeo(void) { sat_position_geo_.UpdateFromEcef(sat_position_ecef_); } +void Orbit::TransEcefToGeo(void) { spacecraft_geodetic_position_.UpdateFromEcef(spacecraft_position_ecef_m_); } OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode) { if (initialize_mode == "DEFAULT") { @@ -70,13 +71,13 @@ std::string Orbit::GetLogHeader() const { std::string Orbit::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(sat_position_i_, 16); - str_tmp += WriteVector(sat_velocity_i_, 10); - str_tmp += WriteVector(sat_velocity_b_, 10); - str_tmp += WriteVector(acc_i_, 10); - str_tmp += WriteScalar(sat_position_geo_.GetLat_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetLon_rad()); - str_tmp += WriteScalar(sat_position_geo_.GetAlt_m()); + str_tmp += WriteVector(spacecraft_position_i_m_, 16); + str_tmp += WriteVector(spacecraft_velocity_i_m_s_, 10); + str_tmp += WriteVector(spacecraft_velocity_b_m_s_, 10); + str_tmp += WriteVector(spacecraft_acceleration_i_m_s2_, 10); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLat_rad()); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLon_rad()); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetAlt_m()); return str_tmp; } diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index ed0789e33..149110a72 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -69,7 +69,7 @@ class Orbit : public ILoggable { * @brief Update attitude information * @param [in] q_i2b: End time of simulation [sec] */ - inline void UpdateAtt(libra::Quaternion q_i2b) { sat_velocity_b_ = q_i2b.frame_conv(sat_velocity_i_); } + inline void UpdateAtt(libra::Quaternion q_i2b) { spacecraft_velocity_b_m_s_ = q_i2b.frame_conv(spacecraft_velocity_i_m_s_); } /** * @fn AddPositionOffset @@ -94,42 +94,42 @@ class Orbit : public ILoggable { * @fn GetSatPosition_i * @brief Return spacecraft position in the inertial frame [m] */ - inline libra::Vector<3> GetSatPosition_i() const { return sat_position_i_; } + inline libra::Vector<3> GetSatPosition_i() const { return spacecraft_position_i_m_; } /** * @fn GetSatPosition_ecef * @brief Return spacecraft position in the ECEF frame [m] */ - inline libra::Vector<3> GetSatPosition_ecef() const { return sat_position_ecef_; } + inline libra::Vector<3> GetSatPosition_ecef() const { return spacecraft_position_ecef_m_; } /** * @fn GetSatVelocity_i * @brief Return spacecraft velocity in the inertial frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_i() const { return sat_velocity_i_; } + inline libra::Vector<3> GetSatVelocity_i() const { return spacecraft_velocity_i_m_s_; } /** * @fn GetSatVelocity_b * @brief Return spacecraft velocity in the body fixed frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_b() const { return sat_velocity_b_; } + inline libra::Vector<3> GetSatVelocity_b() const { return spacecraft_velocity_b_m_s_; } /** * @fn GetSatVelocity_ecef * @brief Return spacecraft velocity in the ECEF frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_ecef() const { return sat_velocity_ecef_; } + inline libra::Vector<3> GetSatVelocity_ecef() const { return spacecraft_velocity_ecef_m_s_; } /** * @fn GetGeodeticPosition * @brief Return spacecraft position in the geodetic frame [m] */ - inline GeodeticPosition GetGeodeticPosition() const { return sat_position_geo_; } + inline GeodeticPosition GetGeodeticPosition() const { return spacecraft_geodetic_position_; } // TODO delete the following functions - inline double GetLat_rad() const { return sat_position_geo_.GetLat_rad(); } - inline double GetLon_rad() const { return sat_position_geo_.GetLon_rad(); } - inline double GetAlt_m() const { return sat_position_geo_.GetAlt_m(); } + inline double GetLat_rad() const { return spacecraft_geodetic_position_.GetLat_rad(); } + inline double GetLon_rad() const { return spacecraft_geodetic_position_.GetLon_rad(); } + inline double GetAlt_m() const { return spacecraft_geodetic_position_.GetAlt_m(); } inline libra::Vector<3> GetLatLonAlt() const { libra::Vector<3> vec; - vec(0) = sat_position_geo_.GetLat_rad(); - vec(1) = sat_position_geo_.GetLon_rad(); - vec(2) = sat_position_geo_.GetAlt_m(); + vec(0) = spacecraft_geodetic_position_.GetLat_rad(); + vec(1) = spacecraft_geodetic_position_.GetLon_rad(); + vec(2) = spacecraft_geodetic_position_.GetAlt_m(); return vec; } @@ -143,7 +143,7 @@ class Orbit : public ILoggable { * @fn SetAcceleration_i * @brief Set acceleration in the inertial frame [m/s2] */ - inline void SetAcceleration_i(libra::Vector<3> acceleration_i) { acc_i_ = acceleration_i; } + inline void SetAcceleration_i(libra::Vector<3> acceleration_i) { spacecraft_acceleration_i_m_s2_ = acceleration_i; } /** * @fn AddForce_i * @brief Add force @@ -152,13 +152,13 @@ class Orbit : public ILoggable { */ inline void AddForce_i(libra::Vector<3> force_i, double spacecraft_mass) { force_i /= spacecraft_mass; - acc_i_ += force_i; + spacecraft_acceleration_i_m_s2_ += force_i; } /** * @fn AddAcceleration_i_m_s2 * @brief Add acceleration in the inertial frame [m/s2] */ - inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i) { acc_i_ += acceleration_i; } + inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i) { spacecraft_acceleration_i_m_s2_ += acceleration_i; } /** * @fn AddForce_i * @brief Add force @@ -196,16 +196,16 @@ class Orbit : public ILoggable { bool is_calc_enabled_ = false; //!< Calculate flag OrbitPropagateMode propagate_mode_; //!< Propagation mode - libra::Vector<3> sat_position_i_; //!< Spacecraft position in the inertial frame [m] - libra::Vector<3> sat_position_ecef_; //!< Spacecraft position in the ECEF frame [m] - GeodeticPosition sat_position_geo_; //!< Spacecraft position in the Geodetic frame + libra::Vector<3> spacecraft_position_i_m_; //!< Spacecraft position in the inertial frame [m] + libra::Vector<3> spacecraft_position_ecef_m_; //!< Spacecraft position in the ECEF frame [m] + GeodeticPosition spacecraft_geodetic_position_; //!< Spacecraft position in the Geodetic frame - libra::Vector<3> sat_velocity_i_; //!< Spacecraft velocity in the inertial frame [m/s] - libra::Vector<3> sat_velocity_b_; //!< Spacecraft velocity in the body frame [m/s] - libra::Vector<3> sat_velocity_ecef_; //!< Spacecraft velocity in the ECEF frame [m/s] + libra::Vector<3> spacecraft_velocity_i_m_s_; //!< Spacecraft velocity in the inertial frame [m/s] + libra::Vector<3> spacecraft_velocity_b_m_s_; //!< Spacecraft velocity in the body frame [m/s] + libra::Vector<3> spacecraft_velocity_ecef_m_s_; //!< Spacecraft velocity in the ECEF frame [m/s] - libra::Vector<3> acc_i_; //!< Spacecraft acceleration in the inertial frame [m/s2] - //!< NOTE: Clear to zero at the end of the Propagate function + libra::Vector<3> spacecraft_acceleration_i_m_s2_; //!< Spacecraft acceleration in the inertial frame [m/s2] + //!< NOTE: Clear to zero at the end of the Propagate function // Frame Conversion TODO: consider other planet /** diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 968ad1972..cd6a1e4d2 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -35,14 +35,14 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve relative_velocity_lvlh_ = initial_relative_velocity_lvlh; // Disturbance acceleration are not considered in relative orbit propagation - acc_i_ *= 0; + spacecraft_acceleration_i_m_s2_ *= 0; Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatPosition_i(); Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatVelocity_i(); Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternionI2LVLH(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); - sat_position_i_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; - sat_velocity_i_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; + spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; initial_state_[0] = initial_relative_position_lvlh[0]; initial_state_[1] = initial_relative_position_lvlh[1]; @@ -94,7 +94,7 @@ void RelativeOrbit::Propagate(double endtime, double current_jd) { if (!is_calc_enabled_) return; - acc_i_ *= 0; // Disturbance acceleration are not considered in relative orbit propagation + spacecraft_acceleration_i_m_s2_ *= 0; // Disturbance acceleration are not considered in relative orbit propagation if (update_method_ == RK4) { PropagateRK4(endtime); @@ -108,8 +108,8 @@ void RelativeOrbit::Propagate(double endtime, double current_jd) { Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternionI2LVLH(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); - sat_position_i_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; - sat_velocity_i_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; + spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; TransEciToEcef(); TransEcefToGeo(); } diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 7b3d03852..2b65e4b22 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -17,7 +17,7 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_i prop_time_ = 0.0; prop_step_ = timestep; - acc_i_ *= 0; + spacecraft_acceleration_i_m_s2_ *= 0; Initialize(init_position, init_velocity, init_time); } @@ -33,9 +33,9 @@ void Rk4OrbitPropagation::RHS(double t, const Vector& state, Vector& rhs) rhs[0] = vx; rhs[1] = vy; rhs[2] = vz; - rhs[3] = acc_i_[0] - mu / r3 * x; - rhs[4] = acc_i_[1] - mu / r3 * y; - rhs[5] = acc_i_[2] - mu / r3 * z; + rhs[3] = spacecraft_acceleration_i_m_s2_[0] - mu / r3 * x; + rhs[4] = spacecraft_acceleration_i_m_s2_[1] - mu / r3 * y; + rhs[5] = spacecraft_acceleration_i_m_s2_[2] - mu / r3 * z; (void)t; } @@ -52,13 +52,13 @@ void Rk4OrbitPropagation::Initialize(Vector<3> init_position, Vector<3> init_vel setup(init_time, init_state); // initialize - acc_i_ *= 0; - sat_position_i_[0] = init_state[0]; - sat_position_i_[1] = init_state[1]; - sat_position_i_[2] = init_state[2]; - sat_velocity_i_[0] = init_state[3]; - sat_velocity_i_[1] = init_state[4]; - sat_velocity_i_[2] = init_state[5]; + spacecraft_acceleration_i_m_s2_ *= 0; + spacecraft_position_i_m_[0] = init_state[0]; + spacecraft_position_i_m_[1] = init_state[1]; + spacecraft_position_i_m_[2] = init_state[2]; + spacecraft_velocity_i_m_s_[0] = init_state[3]; + spacecraft_velocity_i_m_s_[1] = init_state[4]; + spacecraft_velocity_i_m_s_[2] = init_state[5]; TransEciToEcef(); TransEcefToGeo(); @@ -78,12 +78,12 @@ void Rk4OrbitPropagation::Propagate(double endtime, double current_jd) { Update(); prop_time_ = endtime; - sat_position_i_[0] = state()[0]; - sat_position_i_[1] = state()[1]; - sat_position_i_[2] = state()[2]; - sat_velocity_i_[0] = state()[3]; - sat_velocity_i_[1] = state()[4]; - sat_velocity_i_[2] = state()[5]; + spacecraft_position_i_m_[0] = state()[0]; + spacecraft_position_i_m_[1] = state()[1]; + spacecraft_position_i_m_[2] = state()[2]; + spacecraft_velocity_i_m_s_[0] = state()[3]; + spacecraft_velocity_i_m_s_[1] = state()[4]; + spacecraft_velocity_i_m_s_[2] = state()[5]; TransEciToEcef(); TransEcefToGeo(); @@ -95,7 +95,7 @@ void Rk4OrbitPropagation::AddPositionOffset(Vector<3> offset_i) { newstate[i] += offset_i[i]; } setup(x(), newstate); - sat_position_i_[0] = state()[0]; - sat_position_i_[1] = state()[1]; - sat_position_i_[2] = state()[2]; + spacecraft_position_i_m_[0] = state()[0]; + spacecraft_position_i_m_[1] = state()[1]; + spacecraft_position_i_m_[2] = state()[2]; } diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index cff8be535..2cd01023a 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -27,7 +27,7 @@ Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial twoline2rv(tle1, tle2, typerun, typeinput, whichconst_, startmfe, stopmfe, deltamin, satrec_); - acc_i_ *= 0; + spacecraft_acceleration_i_m_s2_ *= 0; // To calculate initial position and velocity is_calc_enabled_ = true; @@ -50,8 +50,8 @@ void Sgp4OrbitPropagation::Propagate(double endtime, double current_jd) { if (satrec_.error > 0) printf("# *** error: time:= %f *** code = %3d\n", satrec_.t, satrec_.error); for (int i = 0; i < 3; ++i) { - sat_position_i_[i] = r[i] * 1000; - sat_velocity_i_[i] = v[i] * 1000; + spacecraft_position_i_m_[i] = r[i] * 1000; + spacecraft_velocity_i_m_s_[i] = v[i] * 1000; } TransEciToEcef(); From 295c54f00343ca2d4c66f2d9998387ea9760db81 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:27:54 +0100 Subject: [PATCH 0591/1086] Fix private function name --- src/dynamics/orbit/encke_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/kepler_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/orbit.cpp | 4 ++-- src/dynamics/orbit/orbit.hpp | 8 ++++---- src/dynamics/orbit/relative_orbit.cpp | 8 ++++---- src/dynamics/orbit/rk4_orbit_propagation.cpp | 8 ++++---- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 4 ++-- 7 files changed, 20 insertions(+), 20 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index c97ebaa5a..df044315d 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -102,8 +102,8 @@ void EnckeOrbitPropagation::UpdateSatOrbit() { spacecraft_position_i_m_ = ref_position_i_m_ + diff_position_i_m_; spacecraft_velocity_i_m_s_ = ref_velocity_i_m_s_ + diff_velocity_i_m_s_; - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } double EnckeOrbitPropagation::CalcQFunction(Vector<3> diff_pos_i) { diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 2aedcaff4..1f34aab83 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -28,6 +28,6 @@ void KeplerOrbitPropagation::UpdateState(const double current_jd) { CalcPosVel(current_jd); spacecraft_position_i_m_ = position_i_m_; spacecraft_velocity_i_m_s_ = velocity_i_m_s_; - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index db05c0c7f..8a8f6236f 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -28,7 +28,7 @@ Quaternion Orbit::CalcQuaternionI2LVLH() const { return q_i2lvlh.normalize(); } -void Orbit::TransEciToEcef(void) { +void Orbit::TransformEciToEcef(void) { libra::Matrix<3, 3> dcm_i_to_xcxf = celestial_information_->GetEarthRotation().GetDcmJ2000ToXcxf(); spacecraft_position_ecef_m_ = dcm_i_to_xcxf * spacecraft_position_i_m_; @@ -40,7 +40,7 @@ void Orbit::TransEciToEcef(void) { spacecraft_velocity_ecef_m_s_ = dcm_i_to_xcxf * V_wExr; } -void Orbit::TransEcefToGeo(void) { spacecraft_geodetic_position_.UpdateFromEcef(spacecraft_position_ecef_m_); } +void Orbit::TransformEcefToGeodetic(void) { spacecraft_geodetic_position_.UpdateFromEcef(spacecraft_position_ecef_m_); } OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode) { if (initialize_mode == "DEFAULT") { diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 149110a72..455d6d09b 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -209,15 +209,15 @@ class Orbit : public ILoggable { // Frame Conversion TODO: consider other planet /** - * @fn TransEciToEcef + * @fn TransformEciToEcef * @brief Transform states from the ECI frame to ECEF frame */ - void TransEciToEcef(void); + void TransformEciToEcef(void); /** - * @fn TransEcefToGeo + * @fn TransformEcefToGeodetic * @brief Transform states from the ECEF frame to the geodetic frame */ - void TransEcefToGeo(void); + void TransformEcefToGeodetic(void); }; OrbitInitializeMode SetOrbitInitializeMode(const std::string initialize_mode); diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index cd6a1e4d2..80676ec9d 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -59,8 +59,8 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve CalculateSTM(stm_model_type_, &(rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit()), mu, 0.0); } - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu) { @@ -110,8 +110,8 @@ void RelativeOrbit::Propagate(double endtime, double current_jd) { spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } void RelativeOrbit::PropagateRK4(double elapsed_sec) { diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 2b65e4b22..ccdee5a3f 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -60,8 +60,8 @@ void Rk4OrbitPropagation::Initialize(Vector<3> init_position, Vector<3> init_vel spacecraft_velocity_i_m_s_[1] = init_state[4]; spacecraft_velocity_i_m_s_[2] = init_state[5]; - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } void Rk4OrbitPropagation::Propagate(double endtime, double current_jd) { @@ -85,8 +85,8 @@ void Rk4OrbitPropagation::Propagate(double endtime, double current_jd) { spacecraft_velocity_i_m_s_[1] = state()[4]; spacecraft_velocity_i_m_s_[2] = state()[5]; - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } void Rk4OrbitPropagation::AddPositionOffset(Vector<3> offset_i) { diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 2cd01023a..2fcd4092e 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -54,8 +54,8 @@ void Sgp4OrbitPropagation::Propagate(double endtime, double current_jd) { spacecraft_velocity_i_m_s_[i] = v[i] * 1000; } - TransEciToEcef(); - TransEcefToGeo(); + TransformEciToEcef(); + TransformEcefToGeodetic(); } Vector<3> Sgp4OrbitPropagation::GetESIOmega() { From d0d53c099cbde1e25c5b301512468a1cf0a2cca8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:33:15 +0100 Subject: [PATCH 0592/1086] Fix function argument names --- .../orbit/encke_orbit_propagation.cpp | 20 ++++++------ .../orbit/encke_orbit_propagation.hpp | 17 +++++----- src/dynamics/orbit/initialize_orbit.cpp | 27 ++++++++-------- src/dynamics/orbit/initialize_orbit.hpp | 8 ++--- .../orbit/kepler_orbit_propagation.cpp | 15 +++++---- .../orbit/kepler_orbit_propagation.hpp | 14 ++++---- src/dynamics/orbit/orbit.hpp | 32 +++++++++---------- src/dynamics/orbit/relative_orbit.cpp | 8 ++--- src/dynamics/orbit/relative_orbit.hpp | 6 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 10 +++--- src/dynamics/orbit/rk4_orbit_propagation.hpp | 6 ++-- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 10 +++--- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 10 +++--- 13 files changed, 93 insertions(+), 90 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index df044315d..a9194032b 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -10,40 +10,40 @@ #include "../../library/orbit/orbital_elements.hpp" EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, - const double current_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, + const double current_time_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, const double error_tolerance) : Orbit(celestial_information), libra::ODE<6>(prop_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), prop_step_s_(prop_step_s) { prop_time_s_ = 0.0; - Initialize(current_jd, init_position_i_m, init_velocity_i_m_s); + Initialize(current_time_jd, init_position_i_m, init_velocity_i_m_s); } EnckeOrbitPropagation::~EnckeOrbitPropagation() {} // Functions for Orbit -void EnckeOrbitPropagation::Propagate(double endtime, double current_jd) { +void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) { if (!is_calc_enabled_) return; // Rectification double norm_sat_position_m = norm(spacecraft_position_i_m_); double norm_diff_position_m = norm(diff_position_i_m_); if (norm_diff_position_m / norm_sat_position_m > error_tolerance_) { - Initialize(current_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); + Initialize(current_time_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); } // Update reference orbit - ref_kepler_orbit.CalcPosVel(current_jd); + ref_kepler_orbit.CalcPosVel(current_time_jd); ref_position_i_m_ = ref_kepler_orbit.GetPosition_i_m(); ref_velocity_i_m_s_ = ref_kepler_orbit.GetVelocity_i_m_s(); // Propagate difference orbit setStepWidth(prop_step_s_); // Re-set propagation Δt - while (endtime - prop_time_s_ - prop_step_s_ > 1.0e-6) { + while (end_time_s - prop_time_s_ - prop_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class prop_time_s_ += prop_step_s_; } - setStepWidth(endtime - prop_time_s_); // Adjust the last propagation Δt + setStepWidth(end_time_s - prop_time_s_); // Adjust the last propagation Δt Update(); - prop_time_s_ = endtime; + prop_time_s_ = end_time_s; diff_position_i_m_[0] = state()[0]; diff_position_i_m_[1] = state()[1]; @@ -78,14 +78,14 @@ void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs } // Private Functions -void EnckeOrbitPropagation::Initialize(double current_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s) { +void EnckeOrbitPropagation::Initialize(double current_time_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s) { // General fill_up(spacecraft_acceleration_i_m_s2_, 0.0); // reference orbit ref_position_i_m_ = init_ref_position_i_m; ref_velocity_i_m_s_ = init_ref_velocity_i_m_s; - OrbitalElements oe_ref(mu_m3_s2_, current_jd, init_ref_position_i_m, init_ref_velocity_i_m_s); + OrbitalElements oe_ref(mu_m3_s2_, current_time_jd, init_ref_position_i_m, init_ref_velocity_i_m_s); ref_kepler_orbit = KeplerOrbit(mu_m3_s2_, oe_ref); // difference orbit diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 8c1fd62ba..6461e021e 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -22,13 +22,14 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] celestial_information: Celestial information * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] prop_step_s: Propagation step width [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] * @param [in] init_position_i_m: Initial value of position in the inertial frame [m] * @param [in] init_velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] * @param [in] error_tolerance: Error tolerance threshold */ - EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, const double current_jd, - const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, const double error_tolerance); + EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, + const double current_time_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, + const double error_tolerance); /** * @fn ~EnckeOrbitPropagation * @brief Destructor @@ -39,10 +40,10 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn Propagate * @brief Propagate orbit - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd); + virtual void Propagate(double end_time_s, double current_time_jd); // Override ODE /** @@ -74,11 +75,11 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn Initialize * @brief Initialize function - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] * @param [in] init_ref_position_i_m: Initial value of reference orbit position in the inertial frame [m] * @param [in] init_ref_velocity_i_m_s: Initial value of reference orbit position in the inertial frame [m] */ - void Initialize(double current_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s); + void Initialize(double current_time_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s); /** * @fn UpdateSatOrbit * @brief Update satellite orbit diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index f60e7f96a..908effed2 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -12,8 +12,8 @@ #include "rk4_orbit_propagation.hpp" #include "sgp4_orbit_propagation.hpp" -Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_jd, double gravity_constant, - std::string section, RelativeInformation* rel_info) { +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_time_jd, + double gravity_constant, std::string section, RelativeInformation* rel_info) { auto conf = IniAccess(ini_path); const char* section_ = section.c_str(); Orbit* orbit; @@ -28,7 +28,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // initialize RK4 orbit propagator Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; @@ -41,7 +41,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string conf.ReadChar(section_, "tle1", 80, tle1); conf.ReadChar(section_, "tle2", 80, tle2); - orbit = new Sgp4OrbitPropagation(celestial_information, tle1, tle2, wgs, current_jd); + orbit = new Sgp4OrbitPropagation(celestial_information, tle1, tle2, wgs, current_time_jd); } else if (propagate_mode == "RELATIVE") { // initialize orbit for relative dynamics of formation flying RelativeOrbit::RelativeOrbitUpdateMethod update_method = @@ -58,8 +58,8 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat int reference_sat_id = conf.ReadInt(section_, "reference_satellite_id"); - orbit = new RelativeOrbit(celestial_information, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, init_relative_velocity_lvlh, - update_method, relative_dynamics_model_type, stm_model_type, rel_info); + orbit = new RelativeOrbit(celestial_information, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, + init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, rel_info); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation double mu_m3_s2 = gravity_constant; @@ -71,7 +71,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string conf.ReadVector<3>(section_, "initial_position_i_m", init_pos_m); Vector<3> init_vel_m_s; conf.ReadVector<3>(section_, "initial_velocity_i_m_s", init_vel_m_s); - oe = OrbitalElements(mu_m3_s2, current_jd, init_pos_m, init_vel_m_s); + oe = OrbitalElements(mu_m3_s2, current_time_jd, init_pos_m, init_vel_m_s); } else { // initialize with orbital elements double semi_major_axis_m = conf.ReadDouble(section_, "semi_major_axis_m"); @@ -83,26 +83,27 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string oe = OrbitalElements(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); } KeplerOrbit kepler_orbit(mu_m3_s2, oe); - orbit = new KeplerOrbitPropagation(celestial_information, current_jd, kepler_orbit); + orbit = new KeplerOrbitPropagation(celestial_information, current_time_jd, kepler_orbit); } else if (propagate_mode == "ENCKE") { // initialize orbit for Encke's method Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } double error_tolerance = conf.ReadDouble(section_, "error_tolerance"); - orbit = new EnckeOrbitPropagation(celestial_information, gravity_constant, stepSec, current_jd, position_i_m, velocity_i_m_s, error_tolerance); + orbit = + new EnckeOrbitPropagation(celestial_information, gravity_constant, stepSec, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); } else { std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; @@ -115,7 +116,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string return orbit; } -Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3_s2, std::string section) { +Vector<6> InitializePosVel(std::string ini_path, double current_time_jd, double mu_m3_s2, std::string section) { auto conf = IniAccess(ini_path); const char* section_ = section.c_str(); Vector<3> position_i_m; @@ -133,7 +134,7 @@ Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3 OrbitalElements oe(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); KeplerOrbit kepler_orbit(mu_m3_s2, oe); - kepler_orbit.CalcPosVel(current_jd); + kepler_orbit.CalcPosVel(current_time_jd); position_i_m = kepler_orbit.GetPosition_i_m(); velocity_i_m_s = kepler_orbit.GetVelocity_i_m_s(); } else if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index 4379d7ed9..881093eb0 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -18,22 +18,22 @@ class RelativeInformation; * @param [in] celestial_information: Celestial information * @param [in] ini_path: Path to initialize file * @param [in] stepSec: Step width [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] * @param [in] gravity_constant: Gravity constant [m3/s2] * @param [in] section: Section name * @param [in] rel_info: Relative information */ -Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_jd, double gravity_constant, +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_time_jd, double gravity_constant, std::string section = "ORBIT", RelativeInformation* rel_info = (RelativeInformation*)nullptr); /** * @fn InitializePosVel * @brief Initialize position and velocity depends on initialize mode * @param [in] ini_path: Path to initialize file - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name */ -Vector<6> InitializePosVel(std::string ini_path, double current_jd, double mu_m3_s2, std::string section = "ORBIT"); +Vector<6> InitializePosVel(std::string ini_path, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); #endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 1f34aab83..9ce051cd2 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -8,24 +8,25 @@ #include "../../library/math/s2e_math.hpp" -KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_jd, KeplerOrbit kepler_orbit) +KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_time_jd, + KeplerOrbit kepler_orbit) : Orbit(celestial_information), KeplerOrbit(kepler_orbit) { - UpdateState(current_jd); + UpdateState(current_time_jd); } KeplerOrbitPropagation::~KeplerOrbitPropagation() {} -void KeplerOrbitPropagation::Propagate(double endtime, double current_jd) { - UNUSED(endtime); +void KeplerOrbitPropagation::Propagate(double end_time_s, double current_time_jd) { + UNUSED(end_time_s); if (!is_calc_enabled_) return; - UpdateState(current_jd); + UpdateState(current_time_jd); } // Private Function -void KeplerOrbitPropagation::UpdateState(const double current_jd) { - CalcPosVel(current_jd); +void KeplerOrbitPropagation::UpdateState(const double current_time_jd) { + CalcPosVel(current_time_jd); spacecraft_position_i_m_ = position_i_m_; spacecraft_velocity_i_m_s_ = velocity_i_m_s_; TransformEciToEcef(); diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index ad401128f..3a7122a8d 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -20,10 +20,10 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { * @fn KeplerOrbitPropagation * @brief Constructor * @param [in] celestial_information: Celestial information - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] * @param [in] kepler_orbit: Kepler orbit */ - KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_jd, KeplerOrbit kepler_orbit); + KeplerOrbitPropagation(const CelestialInformation* celestial_information, const double current_time_jd, KeplerOrbit kepler_orbit); /** * @fn ~KeplerOrbitPropagation * @brief Destructor @@ -34,18 +34,18 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { /** * @fn Propagate * @brief Propagate orbit - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd); + virtual void Propagate(double end_time_s, double current_time_jd); private: /** * @fn UpdateState * @brief Propagate orbit - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] */ - void UpdateState(const double current_jd); + void UpdateState(const double current_time_jd); }; #endif // S2E_DYNAMICS_ORBIT_KEPLER_ORBIT_PROPAGATION_HPP_ diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 455d6d09b..5a1a82b68 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -59,17 +59,17 @@ class Orbit : public ILoggable { /** * @fn Propagate * @brief Pure virtual function for orbit propagation - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd) = 0; + virtual void Propagate(double end_time_s, double current_time_jd) = 0; /** * @fn UpdateAtt * @brief Update attitude information - * @param [in] q_i2b: End time of simulation [sec] + * @param [in] quaternion_i2b: End time of simulation [sec] */ - inline void UpdateAtt(libra::Quaternion q_i2b) { spacecraft_velocity_b_m_s_ = q_i2b.frame_conv(spacecraft_velocity_i_m_s_); } + inline void UpdateAtt(libra::Quaternion quaternion_i2b) { spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); } /** * @fn AddPositionOffset @@ -143,32 +143,32 @@ class Orbit : public ILoggable { * @fn SetAcceleration_i * @brief Set acceleration in the inertial frame [m/s2] */ - inline void SetAcceleration_i(libra::Vector<3> acceleration_i) { spacecraft_acceleration_i_m_s2_ = acceleration_i; } + inline void SetAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ = acceleration_i_m_s2; } /** * @fn AddForce_i * @brief Add force * @param [in] force_i: Force in the inertial frame [N] - * @param [in] spacecraft_mass: Mass of spacecraft [kg] + * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ - inline void AddForce_i(libra::Vector<3> force_i, double spacecraft_mass) { - force_i /= spacecraft_mass; + inline void AddForce_i(libra::Vector<3> force_i, double spacecraft_mass_kg) { + force_i /= spacecraft_mass_kg; spacecraft_acceleration_i_m_s2_ += force_i; } /** * @fn AddAcceleration_i_m_s2 * @brief Add acceleration in the inertial frame [m/s2] */ - inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i) { spacecraft_acceleration_i_m_s2_ += acceleration_i; } + inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ += acceleration_i_m_s2; } /** * @fn AddForce_i * @brief Add force - * @param [in] force_b: Force in the body fixed frame [N] - * @param [in] q_i2b: Quaternion from the inertial frame to the body fixed frame - * @param [in] spacecraft_mass: Mass of spacecraft [kg] + * @param [in] force_b_N: Force in the body fixed frame [N] + * @param [in] quaternion_i2b: Quaternion from the inertial frame to the body fixed frame + * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ - inline void AddForce_b_N(libra::Vector<3> force_b, libra::Quaternion q_i2b, double spacecraft_mass) { - auto force_i = q_i2b.frame_conv_inv(force_b); - AddForce_i(force_i, spacecraft_mass); + inline void AddForce_b_N(libra::Vector<3> force_b_N, libra::Quaternion quaternion_i2b, double spacecraft_mass_kg) { + auto force_i = quaternion_i2b.frame_conv_inv(force_b_N); + AddForce_i(force_i, spacecraft_mass_kg); } /** diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 80676ec9d..fc87c9a63 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -89,18 +89,18 @@ void RelativeOrbit::CalculateSTM(STMModel stm_model_type, const Orbit* reference } } -void RelativeOrbit::Propagate(double endtime, double current_jd) { - UNUSED(current_jd); +void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { + UNUSED(current_time_jd); if (!is_calc_enabled_) return; spacecraft_acceleration_i_m_s2_ *= 0; // Disturbance acceleration are not considered in relative orbit propagation if (update_method_ == RK4) { - PropagateRK4(endtime); + PropagateRK4(end_time_s); } else // update_method_ == STM { - PropagateSTM(endtime); + PropagateSTM(end_time_s); } Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatPosition_i(); diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 13db23084..5da09aad1 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -51,10 +51,10 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { /** * @fn Propagate * @brief Propagate orbit - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd); + virtual void Propagate(double end_time_s, double current_time_jd); // Override ODE /** diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index ccdee5a3f..c77b8cca7 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -64,19 +64,19 @@ void Rk4OrbitPropagation::Initialize(Vector<3> init_position, Vector<3> init_vel TransformEcefToGeodetic(); } -void Rk4OrbitPropagation::Propagate(double endtime, double current_jd) { - UNUSED(current_jd); +void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { + UNUSED(current_time_jd); if (!is_calc_enabled_) return; setStepWidth(prop_step_); // Re-set propagation Δt - while (endtime - prop_time_ - prop_step_ > 1.0e-6) { + while (end_time_s - prop_time_ - prop_step_ > 1.0e-6) { Update(); // Propagation methods of the ODE class prop_time_ += prop_step_; } - setStepWidth(endtime - prop_time_); // Adjust the last propagation Δt + setStepWidth(end_time_s - prop_time_); // Adjust the last propagation Δt Update(); - prop_time_ = endtime; + prop_time_ = end_time_s; spacecraft_position_i_m_[0] = state()[0]; spacecraft_position_i_m_[1] = state()[1]; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 2ddbaaf9a..65986b7a0 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -53,10 +53,10 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn Propagate * @brief Propagate orbit - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd); + virtual void Propagate(double end_time_s, double current_time_jd); /** * @fn AddPositionOffset diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 2fcd4092e..02c23137d 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -10,7 +10,7 @@ #include using namespace std; -Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_jd) +Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_time_jd) : Orbit(celestial_information) { propagate_mode_ = OrbitPropagateMode::kSgp4; @@ -31,15 +31,15 @@ Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial // To calculate initial position and velocity is_calc_enabled_ = true; - Propagate(0.0, current_jd); + Propagate(0.0, current_time_jd); is_calc_enabled_ = false; } -void Sgp4OrbitPropagation::Propagate(double endtime, double current_jd) { - UNUSED(endtime); +void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { + UNUSED(end_time_s); if (!is_calc_enabled_) return; - double elapse_time_min = (current_jd - satrec_.jdsatepoch) * (24.0 * 60.0); + double elapse_time_min = (current_time_jd - satrec_.jdsatepoch) * (24.0 * 60.0); double r[3]; double v[3]; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 50181bfa8..9e84bc096 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -26,18 +26,18 @@ class Sgp4OrbitPropagation : public Orbit { * @param [in] tle1: The first line of TLE * @param [in] tle2: The second line of TLE * @param [in] wgs: Wold Geodetic System - * @param [in] current_jd: Current Julian day [day] + * @param [in] current_time_jd: Current Julian day [day] */ - Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_jd); + Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_time_jd); // Override Orbit /** * @fn Propagate * @brief Propagate orbit - * @param [in] endtime: End time of simulation [sec] - * @param [in] current_jd: Current Julian day [day] + * @param [in] end_time_s: End time of simulation [sec] + * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double endtime, double current_jd); + virtual void Propagate(double end_time_s, double current_time_jd); /** * @fn GetESIOmega From 497cccd2b445c98bed84901cedadf4493cf395d7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:34:18 +0100 Subject: [PATCH 0593/1086] Delete unused public functions --- src/dynamics/orbit/orbit.hpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 5a1a82b68..0217c8137 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -71,14 +71,6 @@ class Orbit : public ILoggable { */ inline void UpdateAtt(libra::Quaternion quaternion_i2b) { spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); } - /** - * @fn AddPositionOffset - * @brief Shift the position of the spacecraft - * @note Is this really needed? - * @param [in] offset_i: Offset vector in the inertial frame [m] - */ - inline virtual void AddPositionOffset(libra::Vector<3> offset_i) { (void)offset_i; } - // Getters /** * @fn GetIsCalcEnabled From 44464d6aa0ef5ef74d9d72857d6b5656e812eead Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:39:48 +0100 Subject: [PATCH 0594/1086] Fix local function variables --- src/dynamics/orbit/orbit.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 8a8f6236f..6b195662a 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -33,11 +33,11 @@ void Orbit::TransformEciToEcef(void) { spacecraft_position_ecef_m_ = dcm_i_to_xcxf * spacecraft_position_i_m_; // convert velocity vector in ECI to the vector in ECEF - libra::Vector<3> OmegaE{0.0}; - OmegaE[2] = environment::earth_mean_angular_velocity_rad_s; - libra::Vector<3> wExr = outer_product(OmegaE, spacecraft_position_i_m_); - libra::Vector<3> V_wExr = spacecraft_velocity_i_m_s_ - wExr; - spacecraft_velocity_ecef_m_s_ = dcm_i_to_xcxf * V_wExr; + libra::Vector<3> earth_angular_velocity_i_rad_s{0.0}; + earth_angular_velocity_i_rad_s[2] = environment::earth_mean_angular_velocity_rad_s; + libra::Vector<3> we_cross_r = outer_product(earth_angular_velocity_i_rad_s, spacecraft_position_i_m_); + libra::Vector<3> velocity_we_cross_r = spacecraft_velocity_i_m_s_ - we_cross_r; + spacecraft_velocity_ecef_m_s_ = dcm_i_to_xcxf * velocity_we_cross_r; } void Orbit::TransformEcefToGeodetic(void) { spacecraft_geodetic_position_.UpdateFromEcef(spacecraft_position_ecef_m_); } From 18ff49d5eb09633280953afa5e5535d437f2825a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:47:59 +0100 Subject: [PATCH 0595/1086] Fix public function name --- src/components/ideal/force_generator.cpp | 4 +- src/components/real/aocs/gnss_receiver.cpp | 6 +-- .../ground_station_calculator.cpp | 4 +- src/disturbances/air_drag.cpp | 2 +- src/disturbances/geopotential.cpp | 4 +- src/disturbances/third_body_gravity.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 4 +- src/dynamics/dynamics.cpp | 6 +-- src/dynamics/orbit/orbit.cpp | 2 +- src/dynamics/orbit/orbit.hpp | 42 ++++++++++--------- src/dynamics/orbit/relative_orbit.cpp | 16 +++---- src/environment/local/local_environment.cpp | 2 +- src/simulation/case/sample_case.cpp | 4 +- .../ground_station/ground_station.cpp | 2 +- .../relative_information.cpp | 24 +++++------ 15 files changed, 63 insertions(+), 61 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index a88bd0e7e..2e47cdbef 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -37,7 +37,7 @@ void ForceGenerator::MainRoutine(int count) { // Convert frame libra::Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); - libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternionI2LVLH(); + libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternion_i2lvlh(); generated_force_i_N_ = q_i2b.frame_conv_inv(generated_force_b_N_); generated_force_rtn_N_ = q_i2rtn.frame_conv(generated_force_i_N_); } @@ -55,7 +55,7 @@ void ForceGenerator::SetForce_i_N(const libra::Vector<3> force_i_N) { void ForceGenerator::SetForce_rtn_N(const libra::Vector<3> force_rtn_N) { libra::Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); - libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternionI2LVLH(); + libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternion_i2lvlh(); libra::Vector<3> force_i_N = q_i2rtn.frame_conv_inv(force_rtn_N); ordered_force_b_N_ = q_i2b.frame_conv(force_i_N); diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index c037bae9a..215df98a8 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -48,15 +48,15 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, Power void GNSSReceiver::MainRoutine(int count) { UNUSED(count); - Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetSatPosition_i(); + Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); CheckAntenna(pos_true_eci_, q_i2b); if (is_gnss_sats_visible_ == 1) { // Antenna of GNSS-R can detect GNSS signal - position_ecef_ = dynamics_->GetOrbit().GetSatPosition_ecef(); + position_ecef_ = dynamics_->GetOrbit().GetPosition_ecef_m(); position_llh_ = dynamics_->GetOrbit().GetLatLonAlt(); - velocity_ecef_ = dynamics_->GetOrbit().GetSatVelocity_ecef(); + velocity_ecef_ = dynamics_->GetOrbit().GetVelocity_ecef_m_s(); AddNoise(pos_true_eci_, position_ecef_); utc_ = simtime_->GetCurrentUtc(); diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index ced6c75cd..6b53caeae 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -65,7 +65,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ } // Free space path loss - Vector<3> sc_pos_i = dynamics.GetOrbit().GetSatPosition_i(); + Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetGSPosition_i(); double dist_sc_gs_km = norm(sc_pos_i - gs_pos_i) / 1000.0; double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / sc_tx_ant.GetFrequency() / 1000.0)); @@ -79,7 +79,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ double phi_on_sc_ant_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_ant_rad)); // SC direction on GS RX antenna frame - Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetSatPosition_ecef() - ground_station.GetGSPosition_ecef(); + Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); gs_to_sc_ecef = libra::normalize(gs_to_sc_ecef); Quaternion q_ecef_to_gs_ant = gs_rx_ant.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.frame_conv(gs_to_sc_ecef); diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index adfca7f9f..a57d4307c 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -24,7 +24,7 @@ AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { double air_density_kg_m3 = local_environment.GetAtmosphere().GetAirDensity_kg_m3(); - Vector<3> velocity_b_m_s = dynamics.GetOrbit().GetSatVelocity_b(); + Vector<3> velocity_b_m_s = dynamics.GetOrbit().GetVelocity_b_m_s(); CalcTorqueForce(velocity_b_m_s, air_density_kg_m3); } diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 9243178be..8b6628c73 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -69,10 +69,10 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam #ifdef DEBUG_GEOPOTENTIAL chrono::system_clock::time_point start, end; start = chrono::system_clock::now(); - debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetSatPosition_ecef(); + debug_pos_ecef_m_ = spacecraft.dynamics_->orbit_->GetPosition_ecef_m(); #endif - CalcAccelerationEcef(dynamics.GetOrbit().GetSatPosition_ecef()); + CalcAccelerationEcef(dynamics.GetOrbit().GetPosition_ecef_m()); #ifdef DEBUG_GEOPOTENTIAL end = chrono::system_clock::now(); time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index aeaec6197..7cbeed512 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -15,7 +15,7 @@ ThirdBodyGravity::~ThirdBodyGravity() {} void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { acceleration_i_m_s2_ = libra::Vector<3>(0.0); // initialize - libra::Vector<3> sc_position_i_m = dynamics.GetOrbit().GetSatPosition_i(); + libra::Vector<3> sc_position_i_m = dynamics.GetOrbit().GetPosition_i_m(); for (auto third_body : third_body_list_) { libra::Vector<3> third_body_position_from_sc_i_m = local_environment.GetCelestialInformation().GetPositionFromSpacecraft_i_m(third_body.c_str()); libra::Vector<3> third_body_pos_i_m = sc_position_i_m + third_body_position_from_sc_i_m; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index eeae34e91..497f38cf0 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -85,9 +85,9 @@ Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { } else if (mode == EARTH_CENTER_POINTING) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("EARTH"); } else if (mode == VELOCITY_DIRECTION_POINTING) { - direction = orbit_->GetSatVelocity_i(); + direction = orbit_->GetVelocity_i_m_s(); } else if (mode == ORBIT_NORMAL_POINTING) { - direction = outer_product(orbit_->GetSatPosition_i(), orbit_->GetSatVelocity_i()); + direction = outer_product(orbit_->GetPosition_i_m(), orbit_->GetVelocity_i_m_s()); } normalize(direction); return direction; diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index c000bafc2..82483971b 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -33,7 +33,7 @@ void Dynamics::Initialize(SimulationConfig* simulation_configuration, const Simu temperature_ = InitTemperature(simulation_configuration->sat_file_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); // To get initial value - orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); + orbit_->UpdateByAttitude(attitude_->GetQuaternion_i2b()); } void Dynamics::Update(const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information) { @@ -46,7 +46,7 @@ void Dynamics::Update(const SimulationTime* simulation_time, const LocalCelestia orbit_->Propagate(simulation_time->GetElapsedTime_s(), simulation_time->GetCurrentTime_jd()); } // Attitude dependent update - orbit_->UpdateAtt(attitude_->GetQuaternion_i2b()); + orbit_->UpdateByAttitude(attitude_->GetQuaternion_i2b()); // Thermal if (simulation_time->GetThermalPropagateFlag()) { @@ -61,7 +61,7 @@ void Dynamics::Update(const SimulationTime* simulation_time, const LocalCelestia void Dynamics::ClearForceTorque(void) { libra::Vector<3> zero(0.0); attitude_->SetTorque_b(zero); - orbit_->SetAcceleration_i(zero); + orbit_->SetAcceleration_i_m_s2(zero); } void Dynamics::LogSetup(Logger& logger) { diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 6b195662a..58e2bb9e9 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -4,7 +4,7 @@ */ #include "orbit.hpp" -Quaternion Orbit::CalcQuaternionI2LVLH() const { +Quaternion Orbit::CalcQuaternion_i2lvlh() const { libra::Vector<3> lvlh_x = spacecraft_position_i_m_; // x-axis in LVLH frame is position vector direction from geocenter to satellite libra::Vector<3> lvlh_ex = normalize(lvlh_x); libra::Vector<3> lvlh_z = diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 0217c8137..a7d529d18 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -65,11 +65,13 @@ class Orbit : public ILoggable { virtual void Propagate(double end_time_s, double current_time_jd) = 0; /** - * @fn UpdateAtt + * @fn UpdateByAttitude * @brief Update attitude information * @param [in] quaternion_i2b: End time of simulation [sec] */ - inline void UpdateAtt(libra::Quaternion quaternion_i2b) { spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); } + inline void UpdateByAttitude(libra::Quaternion quaternion_i2b) { + spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); + } // Getters /** @@ -83,30 +85,30 @@ class Orbit : public ILoggable { */ inline OrbitPropagateMode GetPropagateMode() const { return propagate_mode_; } /** - * @fn GetSatPosition_i + * @fn GetPosition_i_m * @brief Return spacecraft position in the inertial frame [m] */ - inline libra::Vector<3> GetSatPosition_i() const { return spacecraft_position_i_m_; } + inline libra::Vector<3> GetPosition_i_m() const { return spacecraft_position_i_m_; } /** - * @fn GetSatPosition_ecef + * @fn GetPosition_ecef_m * @brief Return spacecraft position in the ECEF frame [m] */ - inline libra::Vector<3> GetSatPosition_ecef() const { return spacecraft_position_ecef_m_; } + inline libra::Vector<3> GetPosition_ecef_m() const { return spacecraft_position_ecef_m_; } /** - * @fn GetSatVelocity_i + * @fn GetVelocity_i_m_s * @brief Return spacecraft velocity in the inertial frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_i() const { return spacecraft_velocity_i_m_s_; } + inline libra::Vector<3> GetVelocity_i_m_s() const { return spacecraft_velocity_i_m_s_; } /** - * @fn GetSatVelocity_b + * @fn GetVelocity_b_m_s * @brief Return spacecraft velocity in the body fixed frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_b() const { return spacecraft_velocity_b_m_s_; } + inline libra::Vector<3> GetVelocity_b_m_s() const { return spacecraft_velocity_b_m_s_; } /** - * @fn GetSatVelocity_ecef + * @fn GetVelocity_ecef_m_s * @brief Return spacecraft velocity in the ECEF frame [m/s] */ - inline libra::Vector<3> GetSatVelocity_ecef() const { return spacecraft_velocity_ecef_m_s_; } + inline libra::Vector<3> GetVelocity_ecef_m_s() const { return spacecraft_velocity_ecef_m_s_; } /** * @fn GetGeodeticPosition * @brief Return spacecraft position in the geodetic frame [m] @@ -132,17 +134,17 @@ class Orbit : public ILoggable { */ inline void SetIsCalcEnabled(bool is_calc_enabled) { is_calc_enabled_ = is_calc_enabled; } /** - * @fn SetAcceleration_i + * @fn SetAcceleration_i_m_s2 * @brief Set acceleration in the inertial frame [m/s2] */ - inline void SetAcceleration_i(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ = acceleration_i_m_s2; } + inline void SetAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ = acceleration_i_m_s2; } /** - * @fn AddForce_i + * @fn AddForce_i_N * @brief Add force * @param [in] force_i: Force in the inertial frame [N] * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ - inline void AddForce_i(libra::Vector<3> force_i, double spacecraft_mass_kg) { + inline void AddForce_i_N(libra::Vector<3> force_i, double spacecraft_mass_kg) { force_i /= spacecraft_mass_kg; spacecraft_acceleration_i_m_s2_ += force_i; } @@ -152,7 +154,7 @@ class Orbit : public ILoggable { */ inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ += acceleration_i_m_s2; } /** - * @fn AddForce_i + * @fn AddForce_i_N * @brief Add force * @param [in] force_b_N: Force in the body fixed frame [N] * @param [in] quaternion_i2b: Quaternion from the inertial frame to the body fixed frame @@ -160,14 +162,14 @@ class Orbit : public ILoggable { */ inline void AddForce_b_N(libra::Vector<3> force_b_N, libra::Quaternion quaternion_i2b, double spacecraft_mass_kg) { auto force_i = quaternion_i2b.frame_conv_inv(force_b_N); - AddForce_i(force_i, spacecraft_mass_kg); + AddForce_i_N(force_i, spacecraft_mass_kg); } /** - * @fn CalcQuaternionI2LVLH + * @fn CalcQuaternion_i2lvlh * @brief Calculate quaternion from the inertial frame to the LVLH frame */ - libra::Quaternion CalcQuaternionI2LVLH() const; + libra::Quaternion CalcQuaternion_i2lvlh() const; // Override ILoggable /** diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index fc87c9a63..69fd9dbc3 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -37,9 +37,9 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve // Disturbance acceleration are not considered in relative orbit propagation spacecraft_acceleration_i_m_s2_ *= 0; - Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatPosition_i(); - Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatVelocity_i(); - Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternionI2LVLH(); + Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetPosition_i_m(); + Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetVelocity_i_m_s(); + Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternion_i2lvlh(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; @@ -66,7 +66,7 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu) { switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { - double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetSatPosition_i()); + double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, mu); } default: { @@ -79,7 +79,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m void RelativeOrbit::CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu, double elapsed_sec) { switch (stm_model_type) { case STMModel::HCW: { - double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetSatPosition_i()); + double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu, elapsed_sec); } default: { @@ -103,9 +103,9 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { PropagateSTM(end_time_s); } - Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatPosition_i(); - Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetSatVelocity_i(); - Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternionI2LVLH(); + Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetPosition_i_m(); + Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetVelocity_i_m_s(); + Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternion_i2lvlh(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index a6c8259e5..73e4d4077 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -54,7 +54,7 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimulationTime* si // Update local environments that depend on the attitude (and the position) if (simulation_time->GetAttitudePropagateFlag()) { - celestial_information_->UpdateAllObjectsInformation(orbit.GetSatPosition_i(), orbit.GetSatVelocity_i(), attitude.GetQuaternion_i2b(), + celestial_information_->UpdateAllObjectsInformation(orbit.GetPosition_i_m(), orbit.GetVelocity_i_m_s(), attitude.GetQuaternion_i2b(), attitude.GetOmega_b()); geomagnetic_field_->CalcMagneticField(simulation_time->GetCurrentDecimalYear(), simulation_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), attitude.GetQuaternion_i2b()); diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index df3b3b44f..1de3c1b15 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -72,8 +72,8 @@ string SampleCase::GetLogHeader() const { string SampleCase::GetLogValue() const { string str_tmp = ""; - // auto pos_i = sample_sat->dynamics_->GetOrbit().GetSatPosition_i(); - // auto vel_i = sample_sat->dynamics_->GetOrbit().GetSatVelocity_i(); + // auto pos_i = sample_sat->dynamics_->GetOrbit().GetPosition_i_m(); + // auto vel_i = sample_sat->dynamics_->GetOrbit().GetVelocity_i_m_s(); // auto quat_i2b = sample_sat->dynamics_->GetAttitude().GetQuaternion_i2b(); // auto omega_b = sample_sat->dynamics_->GetAttitude().GetOmega_b(); diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index d536116f6..dd0b09717 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -48,7 +48,7 @@ void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacec Matrix<3, 3> dcm_ecef2eci = transpose(celes_rotation.GetDcmJ2000ToXcxf()); gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; - is_visible_[spacecraft.GetSatID()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetSatPosition_ecef()); + is_visible_[spacecraft.GetSatID()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); } bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 9cfa1c924..ee5c76eeb 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -13,8 +13,8 @@ void RelativeInformation::Update() { for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { for (size_t reference_sat_id = 0; reference_sat_id < dynamics_database_.size(); reference_sat_id++) { // Position - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetSatPosition_i(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetSatPosition_i(); + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); rel_pos_list_i_m_[target_sat_id][reference_sat_id] = target_sat_pos_i - reference_sat_pos_i; rel_pos_list_rtn_m_[target_sat_id][reference_sat_id] = CalcRelativePosition_rtn_m(target_sat_id, reference_sat_id); @@ -22,8 +22,8 @@ void RelativeInformation::Update() { rel_distance_list_m_[target_sat_id][reference_sat_id] = norm(rel_pos_list_i_m_[target_sat_id][reference_sat_id]); // Velocity - libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetSatVelocity_i(); - libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetSatVelocity_i(); + libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); + libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetVelocity_i_m_s(); rel_vel_list_i_m_s_[target_sat_id][reference_sat_id] = target_sat_vel_i - reference_sat_vel_i; rel_vel_list_rtn_m_s_[target_sat_id][reference_sat_id] = CalcRelativeVelocity_rtn_m_s(target_sat_id, reference_sat_id); @@ -115,28 +115,28 @@ libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int } libra::Vector<3> RelativeInformation::CalcRelativePosition_rtn_m(const int target_sat_id, const int reference_sat_id) { - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetSatPosition_i(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetSatPosition_i(); + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); libra::Vector<3> relative_pos_i = target_sat_pos_i - reference_sat_pos_i; // RTN frame for the reference satellite - libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternionI2LVLH(); + libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternion_i2lvlh(); libra::Vector<3> relative_pos_rtn = q_i2rtn.frame_conv(relative_pos_i); return relative_pos_rtn; } libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int target_sat_id, const int reference_sat_id) { - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetSatPosition_i(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetSatPosition_i(); + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); libra::Vector<3> relative_pos_i = target_sat_pos_i - reference_sat_pos_i; // RTN frame for the reference satellite - libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternionI2LVLH(); + libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternion_i2lvlh(); // Rotation vector of RTN frame - libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetSatVelocity_i(); - libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetSatVelocity_i(); + libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetVelocity_i_m_s(); + libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> rot_vec_rtn_i = cross(reference_sat_pos_i, reference_sat_vel_i); double r2_ref = norm(reference_sat_pos_i) * norm(reference_sat_pos_i); rot_vec_rtn_i /= r2_ref; From 12e51cacd1d63dc127659f38c99764a259a9b2df Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:51:23 +0100 Subject: [PATCH 0596/1086] Add const --- src/dynamics/orbit/orbit.hpp | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index a7d529d18..1178be861 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -62,14 +62,14 @@ class Orbit : public ILoggable { * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd) = 0; + virtual void Propagate(const double end_time_s, const double current_time_jd) = 0; /** * @fn UpdateByAttitude * @brief Update attitude information * @param [in] quaternion_i2b: End time of simulation [sec] */ - inline void UpdateByAttitude(libra::Quaternion quaternion_i2b) { + inline void UpdateByAttitude(const libra::Quaternion quaternion_i2b) { spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); } @@ -132,27 +132,28 @@ class Orbit : public ILoggable { * @fn SetIsCalcEnabled * @brief Set calculate flag */ - inline void SetIsCalcEnabled(bool is_calc_enabled) { is_calc_enabled_ = is_calc_enabled; } + inline void SetIsCalcEnabled(const bool is_calc_enabled) { is_calc_enabled_ = is_calc_enabled; } /** * @fn SetAcceleration_i_m_s2 * @brief Set acceleration in the inertial frame [m/s2] */ - inline void SetAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ = acceleration_i_m_s2; } + inline void SetAcceleration_i_m_s2(const libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ = acceleration_i_m_s2; } /** * @fn AddForce_i_N * @brief Add force * @param [in] force_i: Force in the inertial frame [N] * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ - inline void AddForce_i_N(libra::Vector<3> force_i, double spacecraft_mass_kg) { - force_i /= spacecraft_mass_kg; - spacecraft_acceleration_i_m_s2_ += force_i; + inline void AddForce_i_N(const libra::Vector<3> force_i_N, double spacecraft_mass_kg) { + libra::Vector<3> acceleration_i_m_s2 = force_i_N; + acceleration_i_m_s2 /= spacecraft_mass_kg; // FIXME + spacecraft_acceleration_i_m_s2_ += acceleration_i_m_s2; } /** * @fn AddAcceleration_i_m_s2 * @brief Add acceleration in the inertial frame [m/s2] */ - inline void AddAcceleration_i_m_s2(libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ += acceleration_i_m_s2; } + inline void AddAcceleration_i_m_s2(const libra::Vector<3> acceleration_i_m_s2) { spacecraft_acceleration_i_m_s2_ += acceleration_i_m_s2; } /** * @fn AddForce_i_N * @brief Add force @@ -160,14 +161,14 @@ class Orbit : public ILoggable { * @param [in] quaternion_i2b: Quaternion from the inertial frame to the body fixed frame * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ - inline void AddForce_b_N(libra::Vector<3> force_b_N, libra::Quaternion quaternion_i2b, double spacecraft_mass_kg) { + inline void AddForce_b_N(const libra::Vector<3> force_b_N, const libra::Quaternion quaternion_i2b, const double spacecraft_mass_kg) { auto force_i = quaternion_i2b.frame_conv_inv(force_b_N); AddForce_i_N(force_i, spacecraft_mass_kg); } /** * @fn CalcQuaternion_i2lvlh - * @brief Calculate quaternion from the inertial frame to the LVLH frame + * @brief Calculate and return quaternion from the inertial frame to the LVLH frame */ libra::Quaternion CalcQuaternion_i2lvlh() const; From ed94b1d3d701e2d3b37af649f9fc555260baf4fe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:55:14 +0100 Subject: [PATCH 0597/1086] Add libra:: --- .../orbit/encke_orbit_propagation.cpp | 16 +++++++-------- .../orbit/encke_orbit_propagation.hpp | 20 +++++++++---------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index a9194032b..221946bc7 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -10,8 +10,8 @@ #include "../../library/orbit/orbital_elements.hpp" EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, - const double current_time_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, - const double error_tolerance) + const double current_time_jd, const libra::Vector<3> init_position_i_m, + const libra::Vector<3> init_velocity_i_m_s, const double error_tolerance) : Orbit(celestial_information), libra::ODE<6>(prop_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), prop_step_s_(prop_step_s) { prop_time_s_ = 0.0; Initialize(current_time_jd, init_position_i_m, init_velocity_i_m_s); @@ -56,9 +56,9 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) } // Functions for ODE -void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) { +void EnckeOrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { UNUSED(t); - Vector<3> diff_pos_i_m, diff_acc_i_m_s2; + libra::Vector<3> diff_pos_i_m, diff_acc_i_m_s2; for (int i = 0; i < 3; i++) { diff_pos_i_m[i] = state[i]; } @@ -78,7 +78,7 @@ void EnckeOrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs } // Private Functions -void EnckeOrbitPropagation::Initialize(double current_time_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s) { +void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> init_ref_position_i_m, libra::Vector<3> init_ref_velocity_i_m_s) { // General fill_up(spacecraft_acceleration_i_m_s2_, 0.0); @@ -92,7 +92,7 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, Vector<3> init_re fill_up(diff_position_i_m_, 0.0); fill_up(diff_velocity_i_m_s_, 0.0); - Vector<6> zero(0.0f); + libra::Vector<6> zero(0.0f); setup(0.0, zero); UpdateSatOrbit(); @@ -106,11 +106,11 @@ void EnckeOrbitPropagation::UpdateSatOrbit() { TransformEcefToGeodetic(); } -double EnckeOrbitPropagation::CalcQFunction(Vector<3> diff_pos_i) { +double EnckeOrbitPropagation::CalcQFunction(libra::Vector<3> diff_pos_i) { double r2; r2 = inner_product(spacecraft_position_i_m_, spacecraft_position_i_m_); - Vector<3> dr_2r; + libra::Vector<3> dr_2r; dr_2r = diff_pos_i - 2.0 * spacecraft_position_i_m_; double q = inner_product(diff_pos_i, dr_2r) / r2; diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 6461e021e..2d1dafbaf 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -28,7 +28,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] error_tolerance: Error tolerance threshold */ EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, - const double current_time_jd, const Vector<3> init_position_i_m, const Vector<3> init_velocity_i_m_s, + const double current_time_jd, const libra::Vector<3> init_position_i_m, const libra::Vector<3> init_velocity_i_m_s, const double error_tolerance); /** * @fn ~EnckeOrbitPropagation @@ -43,7 +43,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd); + virtual void Propagate(const double end_time_s, const double current_time_jd); // Override ODE /** @@ -53,7 +53,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); + virtual void RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); private: // General @@ -63,13 +63,13 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { double prop_time_s_; //!< Simulation current time for numerical integration by RK4 // reference orbit - Vector<3> ref_position_i_m_; //!< Reference orbit position in the inertial frame [m] - Vector<3> ref_velocity_i_m_s_; //!< Reference orbit velocity in the inertial frame [m/s] - KeplerOrbit ref_kepler_orbit; //!< Reference Kepler orbital element + libra::Vector<3> ref_position_i_m_; //!< Reference orbit position in the inertial frame [m] + libra::Vector<3> ref_velocity_i_m_s_; //!< Reference orbit velocity in the inertial frame [m/s] + KeplerOrbit ref_kepler_orbit; //!< Reference Kepler orbital element // difference orbit - Vector<3> diff_position_i_m_; //!< Difference orbit position in the inertial frame [m] - Vector<3> diff_velocity_i_m_s_; //!< Difference orbit velocity in the inertial frame [m/s] + libra::Vector<3> diff_position_i_m_; //!< Difference orbit position in the inertial frame [m] + libra::Vector<3> diff_velocity_i_m_s_; //!< Difference orbit velocity in the inertial frame [m/s] // functions /** @@ -79,7 +79,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] init_ref_position_i_m: Initial value of reference orbit position in the inertial frame [m] * @param [in] init_ref_velocity_i_m_s: Initial value of reference orbit position in the inertial frame [m] */ - void Initialize(double current_time_jd, Vector<3> init_ref_position_i_m, Vector<3> init_ref_velocity_i_m_s); + void Initialize(const double current_time_jd, const libra::Vector<3> init_ref_position_i_m, const libra::Vector<3> init_ref_velocity_i_m_s); /** * @fn UpdateSatOrbit * @brief Update satellite orbit @@ -90,7 +90,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @brief Calculate Q function * @param [in] diff_pos_i: Difference of position in the inertial frame [m] */ - double CalcQFunction(Vector<3> diff_pos_i); + double CalcQFunction(const libra::Vector<3> diff_pos_i); }; #endif // S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ From 8719723d9cdcc78179ad8ce9863aab7fd0996b49 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 19:59:41 +0100 Subject: [PATCH 0598/1086] Fix private variables --- .../orbit/encke_orbit_propagation.cpp | 80 ++++++++++--------- .../orbit/encke_orbit_propagation.hpp | 24 +++--- 2 files changed, 54 insertions(+), 50 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 221946bc7..522d28001 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -12,8 +12,12 @@ EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, const double current_time_jd, const libra::Vector<3> init_position_i_m, const libra::Vector<3> init_velocity_i_m_s, const double error_tolerance) - : Orbit(celestial_information), libra::ODE<6>(prop_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), prop_step_s_(prop_step_s) { - prop_time_s_ = 0.0; + : Orbit(celestial_information), + libra::ODE<6>(prop_step_s), + mu_m3_s2_(mu_m3_s2), + error_tolerance_(error_tolerance), + propagation_step_s_(prop_step_s) { + propagation_time_s_ = 0.0; Initialize(current_time_jd, init_position_i_m, init_velocity_i_m_s); } @@ -25,32 +29,32 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) // Rectification double norm_sat_position_m = norm(spacecraft_position_i_m_); - double norm_diff_position_m = norm(diff_position_i_m_); - if (norm_diff_position_m / norm_sat_position_m > error_tolerance_) { + double norm_difference_position_m = norm(difference_position_i_m_); + if (norm_difference_position_m / norm_sat_position_m > error_tolerance_) { Initialize(current_time_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); } // Update reference orbit - ref_kepler_orbit.CalcPosVel(current_time_jd); - ref_position_i_m_ = ref_kepler_orbit.GetPosition_i_m(); - ref_velocity_i_m_s_ = ref_kepler_orbit.GetVelocity_i_m_s(); + reference_kepler_orbit.CalcPosVel(current_time_jd); + reference_position_i_m_ = reference_kepler_orbit.GetPosition_i_m(); + reference_velocity_i_m_s_ = reference_kepler_orbit.GetVelocity_i_m_s(); // Propagate difference orbit - setStepWidth(prop_step_s_); // Re-set propagation Δt - while (end_time_s - prop_time_s_ - prop_step_s_ > 1.0e-6) { + setStepWidth(propagation_step_s_); // Re-set propagation Δt + while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class - prop_time_s_ += prop_step_s_; + propagation_time_s_ += propagation_step_s_; } - setStepWidth(end_time_s - prop_time_s_); // Adjust the last propagation Δt + setStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt Update(); - prop_time_s_ = end_time_s; + propagation_time_s_ = end_time_s; - diff_position_i_m_[0] = state()[0]; - diff_position_i_m_[1] = state()[1]; - diff_position_i_m_[2] = state()[2]; - diff_velocity_i_m_s_[0] = state()[3]; - diff_velocity_i_m_s_[1] = state()[4]; - diff_velocity_i_m_s_[2] = state()[5]; + difference_position_i_m_[0] = state()[0]; + difference_position_i_m_[1] = state()[1]; + difference_position_i_m_[2] = state()[2]; + difference_velocity_i_m_s_[0] = state()[3]; + difference_velocity_i_m_s_[1] = state()[4]; + difference_velocity_i_m_s_[2] = state()[5]; UpdateSatOrbit(); } @@ -58,39 +62,39 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) // Functions for ODE void EnckeOrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { UNUSED(t); - libra::Vector<3> diff_pos_i_m, diff_acc_i_m_s2; + libra::Vector<3> difference_position_i_m_m, difference_acc_i_m_s2; for (int i = 0; i < 3; i++) { - diff_pos_i_m[i] = state[i]; + difference_position_i_m_m[i] = state[i]; } - double q_func = CalcQFunction(diff_pos_i_m); - double r_m = norm(ref_position_i_m_); + double q_func = CalcQFunction(difference_position_i_m_m); + double r_m = norm(reference_position_i_m_); double r_m3 = pow(r_m, 3.0); - diff_acc_i_m_s2 = -(mu_m3_s2_ / r_m3) * (q_func * spacecraft_position_i_m_ + diff_pos_i_m) + spacecraft_acceleration_i_m_s2_; + difference_acc_i_m_s2 = -(mu_m3_s2_ / r_m3) * (q_func * spacecraft_position_i_m_ + difference_position_i_m_m) + spacecraft_acceleration_i_m_s2_; rhs[0] = state[3]; rhs[1] = state[4]; rhs[2] = state[5]; - rhs[3] = diff_acc_i_m_s2[0]; - rhs[4] = diff_acc_i_m_s2[1]; - rhs[5] = diff_acc_i_m_s2[2]; + rhs[3] = difference_acc_i_m_s2[0]; + rhs[4] = difference_acc_i_m_s2[1]; + rhs[5] = difference_acc_i_m_s2[2]; } // Private Functions -void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> init_ref_position_i_m, libra::Vector<3> init_ref_velocity_i_m_s) { +void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> reference_position_i_m, libra::Vector<3> reference_velocity_i_m_s) { // General fill_up(spacecraft_acceleration_i_m_s2_, 0.0); // reference orbit - ref_position_i_m_ = init_ref_position_i_m; - ref_velocity_i_m_s_ = init_ref_velocity_i_m_s; - OrbitalElements oe_ref(mu_m3_s2_, current_time_jd, init_ref_position_i_m, init_ref_velocity_i_m_s); - ref_kepler_orbit = KeplerOrbit(mu_m3_s2_, oe_ref); + reference_position_i_m_ = reference_position_i_m; + reference_velocity_i_m_s_ = reference_velocity_i_m_s; + OrbitalElements oe_ref(mu_m3_s2_, current_time_jd, reference_position_i_m, reference_velocity_i_m_s); + reference_kepler_orbit = KeplerOrbit(mu_m3_s2_, oe_ref); // difference orbit - fill_up(diff_position_i_m_, 0.0); - fill_up(diff_velocity_i_m_s_, 0.0); + fill_up(difference_position_i_m_, 0.0); + fill_up(difference_velocity_i_m_s_, 0.0); libra::Vector<6> zero(0.0f); setup(0.0, zero); @@ -99,21 +103,21 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> } void EnckeOrbitPropagation::UpdateSatOrbit() { - spacecraft_position_i_m_ = ref_position_i_m_ + diff_position_i_m_; - spacecraft_velocity_i_m_s_ = ref_velocity_i_m_s_ + diff_velocity_i_m_s_; + spacecraft_position_i_m_ = reference_position_i_m_ + difference_position_i_m_; + spacecraft_velocity_i_m_s_ = reference_velocity_i_m_s_ + difference_velocity_i_m_s_; TransformEciToEcef(); TransformEcefToGeodetic(); } -double EnckeOrbitPropagation::CalcQFunction(libra::Vector<3> diff_pos_i) { +double EnckeOrbitPropagation::CalcQFunction(libra::Vector<3> difference_position_i_m) { double r2; r2 = inner_product(spacecraft_position_i_m_, spacecraft_position_i_m_); libra::Vector<3> dr_2r; - dr_2r = diff_pos_i - 2.0 * spacecraft_position_i_m_; + dr_2r = difference_position_i_m - 2.0 * spacecraft_position_i_m_; - double q = inner_product(diff_pos_i, dr_2r) / r2; + double q = inner_product(difference_position_i_m, dr_2r) / r2; double q_func = q * (q * q + 3.0 * q + 3.0) / (pow(1.0 + q, 1.5) + 1.0); diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 2d1dafbaf..e31887464 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -59,27 +59,27 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { // General const double mu_m3_s2_; //!< Gravity constant of the center body [m3/s2] const double error_tolerance_; //!< Error tolerance ratio - double prop_step_s_; //!< Propagation step width for RK4 - double prop_time_s_; //!< Simulation current time for numerical integration by RK4 + double propagation_step_s_; //!< Propagation step width for RK4 + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 // reference orbit - libra::Vector<3> ref_position_i_m_; //!< Reference orbit position in the inertial frame [m] - libra::Vector<3> ref_velocity_i_m_s_; //!< Reference orbit velocity in the inertial frame [m/s] - KeplerOrbit ref_kepler_orbit; //!< Reference Kepler orbital element + libra::Vector<3> reference_position_i_m_; //!< Reference orbit position in the inertial frame [m] + libra::Vector<3> reference_velocity_i_m_s_; //!< Reference orbit velocity in the inertial frame [m/s] + KeplerOrbit reference_kepler_orbit; //!< Reference Kepler orbital element // difference orbit - libra::Vector<3> diff_position_i_m_; //!< Difference orbit position in the inertial frame [m] - libra::Vector<3> diff_velocity_i_m_s_; //!< Difference orbit velocity in the inertial frame [m/s] + libra::Vector<3> difference_position_i_m_; //!< Difference orbit position in the inertial frame [m] + libra::Vector<3> difference_velocity_i_m_s_; //!< Difference orbit velocity in the inertial frame [m/s] // functions /** * @fn Initialize * @brief Initialize function * @param [in] current_time_jd: Current Julian day [day] - * @param [in] init_ref_position_i_m: Initial value of reference orbit position in the inertial frame [m] - * @param [in] init_ref_velocity_i_m_s: Initial value of reference orbit position in the inertial frame [m] + * @param [in] reference_position_i_m: Initial value of reference orbit position in the inertial frame [m] + * @param [in] reference_velocity_i_m_s: Initial value of reference orbit position in the inertial frame [m] */ - void Initialize(const double current_time_jd, const libra::Vector<3> init_ref_position_i_m, const libra::Vector<3> init_ref_velocity_i_m_s); + void Initialize(const double current_time_jd, const libra::Vector<3> reference_position_i_m, const libra::Vector<3> reference_velocity_i_m_s); /** * @fn UpdateSatOrbit * @brief Update satellite orbit @@ -88,9 +88,9 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn CalcQFunction * @brief Calculate Q function - * @param [in] diff_pos_i: Difference of position in the inertial frame [m] + * @param [in] difference_position_i_m: Difference of position in the inertial frame [m] */ - double CalcQFunction(const libra::Vector<3> diff_pos_i); + double CalcQFunction(const libra::Vector<3> difference_position_i_m); }; #endif // S2E_DYNAMICS_ORBIT_ENCKE_ORBIT_PROPAGATION_HPP_ From d47e194f1efea5ff64ea3c7a00c3e5178ce1656d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:01:56 +0100 Subject: [PATCH 0599/1086] Fix function argument --- src/dynamics/orbit/encke_orbit_propagation.cpp | 12 ++++++------ src/dynamics/orbit/encke_orbit_propagation.hpp | 10 +++++----- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 522d28001..9a9590440 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -9,16 +9,16 @@ #include "../../library/orbit/orbital_elements.hpp" -EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, - const double current_time_jd, const libra::Vector<3> init_position_i_m, - const libra::Vector<3> init_velocity_i_m_s, const double error_tolerance) +EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, + const double propagation_step_s, const double current_time_jd, const libra::Vector<3> position_i_m, + const libra::Vector<3> velocity_i_m_s, const double error_tolerance) : Orbit(celestial_information), - libra::ODE<6>(prop_step_s), + libra::ODE<6>(propagation_step_s), mu_m3_s2_(mu_m3_s2), error_tolerance_(error_tolerance), - propagation_step_s_(prop_step_s) { + propagation_step_s_(propagation_step_s) { propagation_time_s_ = 0.0; - Initialize(current_time_jd, init_position_i_m, init_velocity_i_m_s); + Initialize(current_time_jd, position_i_m, velocity_i_m_s); } EnckeOrbitPropagation::~EnckeOrbitPropagation() {} diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index e31887464..f83421d17 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -21,14 +21,14 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @brief Constructor * @param [in] celestial_information: Celestial information * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] - * @param [in] prop_step_s: Propagation step width [sec] + * @param [in] propagation_step_s: Propagation step width [sec] * @param [in] current_time_jd: Current Julian day [day] - * @param [in] init_position_i_m: Initial value of position in the inertial frame [m] - * @param [in] init_velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] + * @param [in] position_i_m: Initial value of position in the inertial frame [m] + * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] * @param [in] error_tolerance: Error tolerance threshold */ - EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double prop_step_s, - const double current_time_jd, const libra::Vector<3> init_position_i_m, const libra::Vector<3> init_velocity_i_m_s, + EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double propagation_step_s, + const double current_time_jd, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s, const double error_tolerance); /** * @fn ~EnckeOrbitPropagation From 3d16742fe666e954cfc2155cc415aafb212c62d8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:04:53 +0100 Subject: [PATCH 0600/1086] Fix function argument names --- src/dynamics/orbit/initialize_orbit.cpp | 29 ++++++++++++------------- src/dynamics/orbit/initialize_orbit.hpp | 16 +++++++------- 2 files changed, 22 insertions(+), 23 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 908effed2..c665449a0 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -12,9 +12,9 @@ #include "rk4_orbit_propagation.hpp" #include "sgp4_orbit_propagation.hpp" -Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_time_jd, - double gravity_constant, std::string section, RelativeInformation* rel_info) { - auto conf = IniAccess(ini_path); +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string initialize_file, double step_width_s, double current_time_jd, + double mu_m3_s2, std::string section, RelativeInformation* relative_information) { + auto conf = IniAccess(initialize_file); const char* section_ = section.c_str(); Orbit* orbit; @@ -28,12 +28,12 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // initialize RK4 orbit propagator Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant, stepSec, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, mu_m3_s2, step_width_s, position_i_m, velocity_i_m_s); } else if (propagate_mode == "SGP4") { // Initialize SGP4 orbit propagator int wgs = conf.ReadInt(section_, "wgs"); @@ -58,11 +58,11 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat int reference_sat_id = conf.ReadInt(section_, "reference_satellite_id"); - orbit = new RelativeOrbit(celestial_information, gravity_constant, stepSec, reference_sat_id, init_relative_position_lvlh, - init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, rel_info); + orbit = new RelativeOrbit(celestial_information, mu_m3_s2, step_width_s, reference_sat_id, init_relative_position_lvlh, + init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, relative_information); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation - double mu_m3_s2 = gravity_constant; + double mu_m3_s2 = mu_m3_s2; OrbitalElements oe; // TODO: init_mode_kepler should be removed in the next major update if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { @@ -88,27 +88,26 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // initialize orbit for Encke's method Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } double error_tolerance = conf.ReadDouble(section_, "error_tolerance"); - orbit = - new EnckeOrbitPropagation(celestial_information, gravity_constant, stepSec, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); + orbit = new EnckeOrbitPropagation(celestial_information, mu_m3_s2, step_width_s, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); } else { std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(ini_path, current_time_jd, gravity_constant); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant, stepSec, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, mu_m3_s2, step_width_s, position_i_m, velocity_i_m_s); } orbit->SetIsCalcEnabled(conf.ReadEnable(section_, "calculation")); @@ -116,8 +115,8 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string return orbit; } -Vector<6> InitializePosVel(std::string ini_path, double current_time_jd, double mu_m3_s2, std::string section) { - auto conf = IniAccess(ini_path); +Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section) { + auto conf = IniAccess(initialize_file); const char* section_ = section.c_str(); Vector<3> position_i_m; Vector<3> velocity_i_m_s; diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index 881093eb0..e41755506 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -16,24 +16,24 @@ class RelativeInformation; * @fn InitOrbit * @brief Initialize function for Orbit class * @param [in] celestial_information: Celestial information - * @param [in] ini_path: Path to initialize file - * @param [in] stepSec: Step width [sec] + * @param [in] initialize_file: Path to initialize file + * @param [in] step_width_s: Step width [sec] * @param [in] current_time_jd: Current Julian day [day] - * @param [in] gravity_constant: Gravity constant [m3/s2] + * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name - * @param [in] rel_info: Relative information + * @param [in] relative_information: Relative information */ -Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string ini_path, double stepSec, double current_time_jd, double gravity_constant, - std::string section = "ORBIT", RelativeInformation* rel_info = (RelativeInformation*)nullptr); +Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string initialize_file, double step_width_s, double current_time_jd, + double mu_m3_s2, std::string section = "ORBIT", RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** * @fn InitializePosVel * @brief Initialize position and velocity depends on initialize mode - * @param [in] ini_path: Path to initialize file + * @param [in] initialize_file: Path to initialize file * @param [in] current_time_jd: Current Julian day [day] * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name */ -Vector<6> InitializePosVel(std::string ini_path, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); +Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); #endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ From eb4725d67c710614f61b0fb95639f5c5ff3208bd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:11:29 +0100 Subject: [PATCH 0601/1086] Fix private variables --- src/dynamics/orbit/initialize_orbit.cpp | 4 +- src/dynamics/orbit/relative_orbit.cpp | 92 ++++++++++---------- src/dynamics/orbit/relative_orbit.hpp | 32 +++---- src/dynamics/orbit/rk4_orbit_propagation.cpp | 24 ++--- src/dynamics/orbit/rk4_orbit_propagation.hpp | 12 +-- 5 files changed, 83 insertions(+), 81 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index c665449a0..c191972ca 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -56,9 +56,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // There is a possibility that the orbit of the reference sat is not initialized when RelativeOrbit initialization is called To ensure that // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat - int reference_sat_id = conf.ReadInt(section_, "reference_satellite_id"); + int reference_spacecraft_id = conf.ReadInt(section_, "reference_satellite_id"); - orbit = new RelativeOrbit(celestial_information, mu_m3_s2, step_width_s, reference_sat_id, init_relative_position_lvlh, + orbit = new RelativeOrbit(celestial_information, mu_m3_s2, step_width_s, reference_spacecraft_id, init_relative_position_lvlh, init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, relative_information); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 69fd9dbc3..eb8ef6807 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -8,41 +8,42 @@ #include "rk4_orbit_propagation.hpp" -RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu, double timestep, int reference_sat_id, +RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info) : Orbit(celestial_information), libra::ODE<6>(timestep), - mu_(mu), - reference_sat_id_(reference_sat_id), + mu_m3_s2_(mu_m3_s2), + reference_spacecraft_id_(reference_spacecraft_id), update_method_(update_method), relative_dynamics_model_type_(relative_dynamics_model_type), stm_model_type_(stm_model_type), - rel_info_(rel_info) { + relative_information_(rel_info) { propagate_mode_ = OrbitPropagateMode::kRelativeOrbit; - prop_time_ = 0.0; - prop_step_ = timestep; + propagation_time_s_ = 0.0; + propagation_step_s_ = timestep; - InitializeState(initial_relative_position_lvlh, initial_relative_velocity_lvlh, mu); + InitializeState(initial_relative_position_lvlh, initial_relative_velocity_lvlh, mu_m3_s2); } RelativeOrbit::~RelativeOrbit() {} -void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu, double init_time) { - relative_position_lvlh_ = initial_relative_position_lvlh; - relative_velocity_lvlh_ = initial_relative_velocity_lvlh; +void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, + double init_time) { + relative_position_lvlh_m_ = initial_relative_position_lvlh; + relative_velocity_lvlh_m_s_ = initial_relative_velocity_lvlh; // Disturbance acceleration are not considered in relative orbit propagation spacecraft_acceleration_i_m_s2_ *= 0; - Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetPosition_i_m(); - Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetVelocity_i_m_s(); - Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternion_i2lvlh(); + Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); + Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); + Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); - spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; - spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; + spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; initial_state_[0] = initial_relative_position_lvlh[0]; initial_state_[1] = initial_relative_position_lvlh[1]; @@ -53,21 +54,22 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve if (update_method_ == RK4) { setup(init_time, initial_state_); - CalculateSystemMatrix(relative_dynamics_model_type_, &(rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit()), mu); + CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), + mu_m3_s2); } else // update_method_ == STM { - CalculateSTM(stm_model_type_, &(rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit()), mu, 0.0); + CalculateSTM(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2, 0.0); } TransformEciToEcef(); TransformEcefToGeodetic(); } -void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu) { +void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2) { switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, mu); + system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, mu_m3_s2); } default: { // NOT REACHED @@ -76,11 +78,11 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m } } -void RelativeOrbit::CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu, double elapsed_sec) { +void RelativeOrbit::CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { switch (stm_model_type) { case STMModel::HCW: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu, elapsed_sec); + stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu_m3_s2, elapsed_sec); } default: { // NOT REACHED @@ -103,46 +105,46 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { PropagateSTM(end_time_s); } - Vector<3> reference_sat_position_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetPosition_i_m(); - Vector<3> reference_sat_velocity_i = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().GetVelocity_i_m_s(); - Quaternion q_i2lvlh = rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit().CalcQuaternion_i2lvlh(); + Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); + Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); + Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); Quaternion q_lvlh2i = q_i2lvlh.conjugate(); - spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_) + reference_sat_position_i; - spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_) + reference_sat_velocity_i; + spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; TransformEciToEcef(); TransformEcefToGeodetic(); } void RelativeOrbit::PropagateRK4(double elapsed_sec) { - setStepWidth(prop_step_); // Re-set propagation dt - while (elapsed_sec - prop_time_ - prop_step_ > 1.0e-6) { + setStepWidth(propagation_step_s_); // Re-set propagation dt + while (elapsed_sec - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class - prop_time_ += prop_step_; + propagation_time_s_ += propagation_step_s_; } - setStepWidth(elapsed_sec - prop_time_); // Adjust the last propagation dt + setStepWidth(elapsed_sec - propagation_time_s_); // Adjust the last propagation dt Update(); - prop_time_ = elapsed_sec; - - relative_position_lvlh_[0] = state()[0]; - relative_position_lvlh_[1] = state()[1]; - relative_position_lvlh_[2] = state()[2]; - relative_velocity_lvlh_[0] = state()[3]; - relative_velocity_lvlh_[1] = state()[4]; - relative_velocity_lvlh_[2] = state()[5]; + propagation_time_s_ = elapsed_sec; + + relative_position_lvlh_m_[0] = state()[0]; + relative_position_lvlh_m_[1] = state()[1]; + relative_position_lvlh_m_[2] = state()[2]; + relative_velocity_lvlh_m_s_[0] = state()[3]; + relative_velocity_lvlh_m_s_[1] = state()[4]; + relative_velocity_lvlh_m_s_[2] = state()[5]; } void RelativeOrbit::PropagateSTM(double elapsed_sec) { Vector<6> current_state; - CalculateSTM(stm_model_type_, &(rel_info_->GetReferenceSatDynamics(reference_sat_id_)->GetOrbit()), mu_, elapsed_sec); + CalculateSTM(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2_, elapsed_sec); current_state = stm_ * initial_state_; - relative_position_lvlh_[0] = current_state[0]; - relative_position_lvlh_[1] = current_state[1]; - relative_position_lvlh_[2] = current_state[2]; - relative_velocity_lvlh_[0] = current_state[3]; - relative_velocity_lvlh_[1] = current_state[4]; - relative_velocity_lvlh_[2] = current_state[5]; + relative_position_lvlh_m_[0] = current_state[0]; + relative_position_lvlh_m_[1] = current_state[1]; + relative_position_lvlh_m_[2] = current_state[2]; + relative_velocity_lvlh_m_s_[0] = current_state[3]; + relative_velocity_lvlh_m_s_[1] = current_state[4]; + relative_velocity_lvlh_m_s_[2] = current_state[5]; } void RelativeOrbit::RHS(double t, const Vector<6>& state, Vector<6>& rhs) // only for RK4 relative dynamics propagation diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 5da09aad1..d457847b7 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -30,7 +30,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @brief Constructor * @param [in] celestial_information: Celestial information * @param [in] timestep: Time step [sec] - * @param [in] reference_sat_id: Reference satellite ID + * @param [in] reference_spacecraft_id: Reference satellite ID * @param [in] initial_relative_position_lvlh: Initial value of relative position at the LVLH frame of reference satellite * @param [in] initial_relative_velocity_lvlh: Initial value of relative velocity at the LVLH frame of reference satellite * @param [in] update_method: Update method @@ -38,7 +38,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] stm_model_type: State transition matrix type * @param [in] rel_info: Relative information */ - RelativeOrbit(const CelestialInformation* celestial_information, double mu, double timestep, int reference_sat_id, + RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info); /** @@ -67,49 +67,49 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); private: - double mu_; //!< Gravity constant of the center body [m3/s2] - int reference_sat_id_; //!< Reference satellite ID - double prop_time_; //!< Simulation current time for numerical integration by RK4 [sec] - double prop_step_; //!< Step width for RK4 [sec] + double mu_m3_s2_; //!< Gravity constant of the center body [m3/s2] + unsigned int reference_spacecraft_id_; //!< Reference satellite ID + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] + double propagation_step_s_; //!< Step width for RK4 [sec] Matrix<6, 6> system_matrix_; //!< System matrix Matrix<6, 6> stm_; //!< State transition matrix - Vector<6> initial_state_; //!< Initial state (Position and Velocity) - Vector<3> relative_position_lvlh_; //!< Relative position in the LVLH frame - Vector<3> relative_velocity_lvlh_; //!< Relative velocity in the LVLH frame + Vector<6> initial_state_; //!< Initial state (Position and Velocity) + Vector<3> relative_position_lvlh_m_; //!< Relative position in the LVLH frame + Vector<3> relative_velocity_lvlh_m_s_; //!< Relative velocity in the LVLH frame RelativeOrbitUpdateMethod update_method_; //!< Update method RelativeOrbitModel relative_dynamics_model_type_; //!< Relative dynamics model type STMModel stm_model_type_; //!< State Transition Matrix model type - RelativeInformation* rel_info_; //!< Relative information + RelativeInformation* relative_information_; //!< Relative information /** * @fn InitializeState * @brief Initialize state variables * @param [in] initial_relative_position_lvlh: Initial value of relative position at the LVLH frame of reference satellite * @param [in] initial_relative_velocity_lvlh: Initial value of relative velocity at the LVLH frame of reference satellite - * @param [in] mu: Gravity constant of the center body [m3/s2] + * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] init_time: Initialize time [sec] */ - void InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu, double init_time = 0); + void InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, double init_time = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix * @param [in] relative_dynamics_model_type: Relative dynamics model type * @param [in] reference_sat_orbit: Orbit information of reference satellite - * @param [in] mu: Gravity constant of the center body [m3/s2] + * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] */ - void CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu); + void CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2); /** * @fn CalculateSTM * @brief Calculate State Transition Matrix * @param [in] stm_model_type: STM model type * @param [in] reference_sat_orbit: Orbit information of reference satellite - * @param [in] mu: Gravity constant of the center body [m3/s2] + * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] elapsed_sec: Elapsed time [sec] */ - void CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu, double elapsed_sec); + void CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); /** * @fn PropagateRK4 * @brief Propagate relative orbit with RK4 diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index c77b8cca7..7501a556b 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -10,13 +10,13 @@ using std::string; -Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu, double timestep, Vector<3> init_position, +Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, Vector<3> init_position, Vector<3> init_velocity, double init_time) - : Orbit(celestial_information), ODE(timestep), mu(mu) { + : Orbit(celestial_information), ODE(timestep), mu_m3_s2(mu_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; - prop_time_ = 0.0; - prop_step_ = timestep; + propagation_time_s_ = 0.0; + propagation_step_s_ = timestep; spacecraft_acceleration_i_m_s2_ *= 0; Initialize(init_position, init_velocity, init_time); @@ -33,9 +33,9 @@ void Rk4OrbitPropagation::RHS(double t, const Vector& state, Vector& rhs) rhs[0] = vx; rhs[1] = vy; rhs[2] = vz; - rhs[3] = spacecraft_acceleration_i_m_s2_[0] - mu / r3 * x; - rhs[4] = spacecraft_acceleration_i_m_s2_[1] - mu / r3 * y; - rhs[5] = spacecraft_acceleration_i_m_s2_[2] - mu / r3 * z; + rhs[3] = spacecraft_acceleration_i_m_s2_[0] - mu_m3_s2 / r3 * x; + rhs[4] = spacecraft_acceleration_i_m_s2_[1] - mu_m3_s2 / r3 * y; + rhs[5] = spacecraft_acceleration_i_m_s2_[2] - mu_m3_s2 / r3 * z; (void)t; } @@ -69,14 +69,14 @@ void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { if (!is_calc_enabled_) return; - setStepWidth(prop_step_); // Re-set propagation Δt - while (end_time_s - prop_time_ - prop_step_ > 1.0e-6) { + setStepWidth(propagation_step_s_); // Re-set propagation Δt + while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class - prop_time_ += prop_step_; + propagation_time_s_ += propagation_step_s_; } - setStepWidth(end_time_s - prop_time_); // Adjust the last propagation Δt + setStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt Update(); - prop_time_ = end_time_s; + propagation_time_s_ = end_time_s; spacecraft_position_i_m_[0] = state()[0]; spacecraft_position_i_m_[1] = state()[1]; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 65986b7a0..be781571a 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -18,21 +18,21 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { private: static const int N = 6; //!< Degrees of freedom in 3D space - double mu; //!< Gravity constant [m3/s2] + double mu_m3_s2; //!< Gravity constant [m3/s2] public: /** * @fn Rk4OrbitPropagation * @brief Constructor * @param [in] celestial_information: Celestial information - * @param [in] mu: Gravity constant [m3/s2] + * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] timestep: Step width [sec] * @param [in] init_position: Initial value of position in the inertial frame [m] * @param [in] init_velocity: Initial value of velocity in the inertial frame [m/s] * @param [in] init_time: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu, double timestep, Vector<3> init_position, Vector<3> init_velocity, - double init_time = 0); + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, Vector<3> init_position, + Vector<3> init_velocity, double init_time = 0); /** * @fn ~Rk4OrbitPropagation * @brief Destructor @@ -67,8 +67,8 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { virtual void AddPositionOffset(Vector<3> offset_i); private: - double prop_time_; //!< Simulation current time for numerical integration by RK4 [sec] - double prop_step_; //!< Step width for RK4 [sec] + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] + double propagation_step_s_; //!< Step width for RK4 [sec] /** * @fn Initialize From c1a51f6b66e6d02bb9a0d1b099e924ea71fbb4ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:13:45 +0100 Subject: [PATCH 0602/1086] Add libra:: --- src/dynamics/orbit/relative_orbit.cpp | 26 ++++++++++++++------------ src/dynamics/orbit/relative_orbit.hpp | 18 ++++++++++-------- 2 files changed, 24 insertions(+), 20 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index eb8ef6807..68291ee52 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -9,7 +9,7 @@ #include "rk4_orbit_propagation.hpp" RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, - Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, + libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info) : Orbit(celestial_information), @@ -30,7 +30,7 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, RelativeOrbit::~RelativeOrbit() {} -void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, +void RelativeOrbit::InitializeState(libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, double init_time) { relative_position_lvlh_m_ = initial_relative_position_lvlh; relative_velocity_lvlh_m_s_ = initial_relative_velocity_lvlh; @@ -38,10 +38,11 @@ void RelativeOrbit::InitializeState(Vector<3> initial_relative_position_lvlh, Ve // Disturbance acceleration are not considered in relative orbit propagation spacecraft_acceleration_i_m_s2_ *= 0; - Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); - Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); - Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); - Quaternion q_lvlh2i = q_i2lvlh.conjugate(); + libra::Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_velocity_i = + relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); + libra::Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); + libra::Quaternion q_lvlh2i = q_i2lvlh.conjugate(); spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; @@ -105,10 +106,11 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { PropagateSTM(end_time_s); } - Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); - Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); - Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); - Quaternion q_lvlh2i = q_i2lvlh.conjugate(); + libra::Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_velocity_i = + relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); + libra::Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); + libra::Quaternion q_lvlh2i = q_i2lvlh.conjugate(); spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; @@ -135,7 +137,7 @@ void RelativeOrbit::PropagateRK4(double elapsed_sec) { } void RelativeOrbit::PropagateSTM(double elapsed_sec) { - Vector<6> current_state; + libra::Vector<6> current_state; CalculateSTM(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2_, elapsed_sec); current_state = stm_ * initial_state_; @@ -147,7 +149,7 @@ void RelativeOrbit::PropagateSTM(double elapsed_sec) { relative_velocity_lvlh_m_s_[2] = current_state[5]; } -void RelativeOrbit::RHS(double t, const Vector<6>& state, Vector<6>& rhs) // only for RK4 relative dynamics propagation +void RelativeOrbit::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) // only for RK4 relative dynamics propagation { rhs = system_matrix_ * state; (void)t; diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index d457847b7..a9315776a 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -39,8 +39,9 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] rel_info: Relative information */ RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, - Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, RelativeOrbitUpdateMethod update_method, - RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* rel_info); + libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, + RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, + RelativeInformation* rel_info); /** * @fn ~RelativeOrbit * @brief Destructor @@ -72,12 +73,12 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] double propagation_step_s_; //!< Step width for RK4 [sec] - Matrix<6, 6> system_matrix_; //!< System matrix - Matrix<6, 6> stm_; //!< State transition matrix + libra::Matrix<6, 6> system_matrix_; //!< System matrix + libra::Matrix<6, 6> stm_; //!< State transition matrix - Vector<6> initial_state_; //!< Initial state (Position and Velocity) - Vector<3> relative_position_lvlh_m_; //!< Relative position in the LVLH frame - Vector<3> relative_velocity_lvlh_m_s_; //!< Relative velocity in the LVLH frame + libra::Vector<6> initial_state_; //!< Initial state (Position and Velocity) + libra::Vector<3> relative_position_lvlh_m_; //!< Relative position in the LVLH frame + libra::Vector<3> relative_velocity_lvlh_m_s_; //!< Relative velocity in the LVLH frame RelativeOrbitUpdateMethod update_method_; //!< Update method RelativeOrbitModel relative_dynamics_model_type_; //!< Relative dynamics model type @@ -92,7 +93,8 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] init_time: Initialize time [sec] */ - void InitializeState(Vector<3> initial_relative_position_lvlh, Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, double init_time = 0); + void InitializeState(libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, + double init_time = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix From 88703ef56943339fc88dc09386e1ad3bf437c96d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:18:07 +0100 Subject: [PATCH 0603/1086] Fix private function names --- src/dynamics/orbit/relative_orbit.cpp | 50 ++++++++++---------- src/dynamics/orbit/relative_orbit.hpp | 34 +++++++------ src/dynamics/orbit/rk4_orbit_propagation.cpp | 8 ++-- src/dynamics/orbit/rk4_orbit_propagation.hpp | 4 +- 4 files changed, 47 insertions(+), 49 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 68291ee52..0bc9217ce 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -8,35 +8,35 @@ #include "rk4_orbit_propagation.hpp" -RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, - libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, +RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, + libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, - RelativeInformation* rel_info) + RelativeInformation* relative_information) : Orbit(celestial_information), - libra::ODE<6>(timestep), + libra::ODE<6>(time_step_s), mu_m3_s2_(mu_m3_s2), reference_spacecraft_id_(reference_spacecraft_id), update_method_(update_method), relative_dynamics_model_type_(relative_dynamics_model_type), stm_model_type_(stm_model_type), - relative_information_(rel_info) { + relative_information_(relative_information) { propagate_mode_ = OrbitPropagateMode::kRelativeOrbit; propagation_time_s_ = 0.0; - propagation_step_s_ = timestep; + propagation_step_s_ = time_step_s; - InitializeState(initial_relative_position_lvlh, initial_relative_velocity_lvlh, mu_m3_s2); + InitializeState(relative_position_lvlh_m, relative_velocity_lvlh_m_s, mu_m3_s2); } RelativeOrbit::~RelativeOrbit() {} -void RelativeOrbit::InitializeState(libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, +void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, double init_time) { - relative_position_lvlh_m_ = initial_relative_position_lvlh; - relative_velocity_lvlh_m_s_ = initial_relative_velocity_lvlh; + relative_position_lvlh_m_ = relative_position_lvlh_m; + relative_velocity_lvlh_m_s_ = relative_velocity_lvlh_m_s; // Disturbance acceleration are not considered in relative orbit propagation - spacecraft_acceleration_i_m_s2_ *= 0; + spacecraft_acceleration_i_m_s2_ *= 0.0; libra::Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); libra::Vector<3> reference_sat_velocity_i = @@ -46,12 +46,12 @@ void RelativeOrbit::InitializeState(libra::Vector<3> initial_relative_position_l spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; - initial_state_[0] = initial_relative_position_lvlh[0]; - initial_state_[1] = initial_relative_position_lvlh[1]; - initial_state_[2] = initial_relative_position_lvlh[2]; - initial_state_[3] = initial_relative_velocity_lvlh[0]; - initial_state_[4] = initial_relative_velocity_lvlh[1]; - initial_state_[5] = initial_relative_velocity_lvlh[2]; + initial_state_[0] = relative_position_lvlh_m[0]; + initial_state_[1] = relative_position_lvlh_m[1]; + initial_state_[2] = relative_position_lvlh_m[2]; + initial_state_[3] = relative_velocity_lvlh_m_s[0]; + initial_state_[4] = relative_velocity_lvlh_m_s[1]; + initial_state_[5] = relative_velocity_lvlh_m_s[2]; if (update_method_ == RK4) { setup(init_time, initial_state_); @@ -59,7 +59,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> initial_relative_position_l mu_m3_s2); } else // update_method_ == STM { - CalculateSTM(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2, 0.0); + CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2, 0.0); } TransformEciToEcef(); @@ -79,7 +79,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m } } -void RelativeOrbit::CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { +void RelativeOrbit::CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { switch (stm_model_type) { case STMModel::HCW: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); @@ -97,13 +97,13 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { if (!is_calc_enabled_) return; - spacecraft_acceleration_i_m_s2_ *= 0; // Disturbance acceleration are not considered in relative orbit propagation + spacecraft_acceleration_i_m_s2_ *= 0.0; // Disturbance acceleration are not considered in relative orbit propagation if (update_method_ == RK4) { - PropagateRK4(end_time_s); + PropagateRk4(end_time_s); } else // update_method_ == STM { - PropagateSTM(end_time_s); + PropagateStm(end_time_s); } libra::Vector<3> reference_sat_position_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetPosition_i_m(); @@ -118,7 +118,7 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { TransformEcefToGeodetic(); } -void RelativeOrbit::PropagateRK4(double elapsed_sec) { +void RelativeOrbit::PropagateRk4(double elapsed_sec) { setStepWidth(propagation_step_s_); // Re-set propagation dt while (elapsed_sec - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class @@ -136,9 +136,9 @@ void RelativeOrbit::PropagateRK4(double elapsed_sec) { relative_velocity_lvlh_m_s_[2] = state()[5]; } -void RelativeOrbit::PropagateSTM(double elapsed_sec) { +void RelativeOrbit::PropagateStm(double elapsed_sec) { libra::Vector<6> current_state; - CalculateSTM(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2_, elapsed_sec); + CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2_, elapsed_sec); current_state = stm_ * initial_state_; relative_position_lvlh_m_[0] = current_state[0]; diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index a9315776a..97783419c 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -29,19 +29,18 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @fn RelativeOrbit * @brief Constructor * @param [in] celestial_information: Celestial information - * @param [in] timestep: Time step [sec] + * @param [in] time_step_s: Time step [sec] * @param [in] reference_spacecraft_id: Reference satellite ID - * @param [in] initial_relative_position_lvlh: Initial value of relative position at the LVLH frame of reference satellite - * @param [in] initial_relative_velocity_lvlh: Initial value of relative velocity at the LVLH frame of reference satellite + * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite + * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite * @param [in] update_method: Update method * @param [in] relative_dynamics_model_type: Relative dynamics model type * @param [in] stm_model_type: State transition matrix type - * @param [in] rel_info: Relative information + * @param [in] relative_information: Relative information */ - RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, int reference_spacecraft_id, - libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, - RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, - RelativeInformation* rel_info); + RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, + libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, RelativeOrbitUpdateMethod update_method, + RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* relative_information); /** * @fn ~RelativeOrbit * @brief Destructor @@ -88,13 +87,12 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { /** * @fn InitializeState * @brief Initialize state variables - * @param [in] initial_relative_position_lvlh: Initial value of relative position at the LVLH frame of reference satellite - * @param [in] initial_relative_velocity_lvlh: Initial value of relative velocity at the LVLH frame of reference satellite + * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite + * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] init_time: Initialize time [sec] */ - void InitializeState(libra::Vector<3> initial_relative_position_lvlh, libra::Vector<3> initial_relative_velocity_lvlh, double mu_m3_s2, - double init_time = 0); + void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, double init_time = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix @@ -104,26 +102,26 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { */ void CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2); /** - * @fn CalculateSTM + * @fn CalculateStm * @brief Calculate State Transition Matrix * @param [in] stm_model_type: STM model type * @param [in] reference_sat_orbit: Orbit information of reference satellite * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] elapsed_sec: Elapsed time [sec] */ - void CalculateSTM(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); + void CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); /** - * @fn PropagateRK4 + * @fn PropagateRk4 * @brief Propagate relative orbit with RK4 * @param [in] elapsed_sec: Elapsed time [sec] */ - void PropagateRK4(double elapsed_sec); + void PropagateRk4(double elapsed_sec); /** - * @fn PropagateSTM + * @fn PropagateStm * @brief Propagate relative orbit with STM * @param [in] elapsed_sec: Elapsed time [sec] */ - void PropagateSTM(double elapsed_sec); + void PropagateStm(double elapsed_sec); }; #endif // S2E_DYNAMICS_ORBIT_RELATIVE_ORBIT_HPP_ diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 7501a556b..7cd1237c2 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -10,13 +10,13 @@ using std::string; -Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, Vector<3> init_position, - Vector<3> init_velocity, double init_time) - : Orbit(celestial_information), ODE(timestep), mu_m3_s2(mu_m3_s2) { +Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, + Vector<3> init_position, Vector<3> init_velocity, double init_time) + : Orbit(celestial_information), ODE(time_step_s), mu_m3_s2(mu_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; propagation_time_s_ = 0.0; - propagation_step_s_ = timestep; + propagation_step_s_ = time_step_s; spacecraft_acceleration_i_m_s2_ *= 0; Initialize(init_position, init_velocity, init_time); diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index be781571a..91f99b487 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -26,12 +26,12 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @brief Constructor * @param [in] celestial_information: Celestial information * @param [in] mu_m3_s2: Gravity constant [m3/s2] - * @param [in] timestep: Step width [sec] + * @param [in] time_step_s: Step width [sec] * @param [in] init_position: Initial value of position in the inertial frame [m] * @param [in] init_velocity: Initial value of velocity in the inertial frame [m/s] * @param [in] init_time: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double timestep, Vector<3> init_position, + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); /** * @fn ~Rk4OrbitPropagation From f3e7ec3aee3eadc6999203fcd243992633031333 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:23:13 +0100 Subject: [PATCH 0604/1086] Fix unnecessary private variables --- src/dynamics/orbit/rk4_orbit_propagation.cpp | 6 +++--- src/dynamics/orbit/rk4_orbit_propagation.hpp | 9 ++++----- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 7cd1237c2..79bdd4c4c 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -12,7 +12,7 @@ using std::string; Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, Vector<3> init_position, Vector<3> init_velocity, double init_time) - : Orbit(celestial_information), ODE(time_step_s), mu_m3_s2(mu_m3_s2) { + : Orbit(celestial_information), ODE<6>(time_step_s), mu_m3_s2(mu_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; propagation_time_s_ = 0.0; @@ -24,7 +24,7 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_i Rk4OrbitPropagation::~Rk4OrbitPropagation() {} -void Rk4OrbitPropagation::RHS(double t, const Vector& state, Vector& rhs) { +void Rk4OrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) { double x = state[0], y = state[1], z = state[2]; double vx = state[3], vy = state[4], vz = state[5]; @@ -42,7 +42,7 @@ void Rk4OrbitPropagation::RHS(double t, const Vector& state, Vector& rhs) void Rk4OrbitPropagation::Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time) { // state vector [x,y,z,vx,vy,vz] - Vector init_state; + Vector<6> init_state; init_state[0] = init_position[0]; init_state[1] = init_position[1]; init_state[2] = init_position[2]; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 91f99b487..860c4e47f 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -16,10 +16,6 @@ * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { - private: - static const int N = 6; //!< Degrees of freedom in 3D space - double mu_m3_s2; //!< Gravity constant [m3/s2] - public: /** * @fn Rk4OrbitPropagation @@ -47,7 +43,7 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const Vector& state, Vector& rhs); + virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); // Override Orbit /** @@ -78,6 +74,9 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] init_time: Initial time [sec] */ void Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); + + private: + double mu_m3_s2; //!< Gravity constant [m3/s2] }; #endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ From e56bd09210451a116fef39107fb08e4f09d0154a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:24:33 +0100 Subject: [PATCH 0605/1086] Remove unused public functions --- src/dynamics/orbit/rk4_orbit_propagation.cpp | 11 ----------- src/dynamics/orbit/rk4_orbit_propagation.hpp | 12 +----------- 2 files changed, 1 insertion(+), 22 deletions(-) diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 79bdd4c4c..a29ed88a2 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -88,14 +88,3 @@ void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { TransformEciToEcef(); TransformEcefToGeodetic(); } - -void Rk4OrbitPropagation::AddPositionOffset(Vector<3> offset_i) { - auto newstate = state(); - for (auto i = 0; i < 3; i++) { - newstate[i] += offset_i[i]; - } - setup(x(), newstate); - spacecraft_position_i_m_[0] = state()[0]; - spacecraft_position_i_m_[1] = state()[1]; - spacecraft_position_i_m_[2] = state()[2]; -} diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 860c4e47f..7207bfd78 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -54,15 +54,8 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { */ virtual void Propagate(double end_time_s, double current_time_jd); - /** - * @fn AddPositionOffset - * @brief Shift the position of the spacecraft - * @note Is this really needed? - * @param [in] offset_i: Offset vector in the inertial frame [m] - */ - virtual void AddPositionOffset(Vector<3> offset_i); - private: + double mu_m3_s2; //!< Gravity constant [m3/s2] double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] double propagation_step_s_; //!< Step width for RK4 [sec] @@ -74,9 +67,6 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] init_time: Initial time [sec] */ void Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); - - private: - double mu_m3_s2; //!< Gravity constant [m3/s2] }; #endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ From 4cd96db764fbe2c7bfb38289d6ff4795641c964e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:26:29 +0100 Subject: [PATCH 0606/1086] Fix function argument name --- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/orbit/relative_orbit.hpp | 5 +++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 20 ++++++++++---------- src/dynamics/orbit/rk4_orbit_propagation.hpp | 18 +++++++++--------- 4 files changed, 24 insertions(+), 23 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 0bc9217ce..25827a635 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -31,7 +31,7 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, RelativeOrbit::~RelativeOrbit() {} void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, - double init_time) { + double initiali_time_s) { relative_position_lvlh_m_ = relative_position_lvlh_m; relative_velocity_lvlh_m_s_ = relative_velocity_lvlh_m_s; @@ -54,7 +54,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l initial_state_[5] = relative_velocity_lvlh_m_s[2]; if (update_method_ == RK4) { - setup(init_time, initial_state_); + setup(initiali_time_s, initial_state_); CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2); } else // update_method_ == STM diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 97783419c..8a45fff09 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -90,9 +90,10 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] - * @param [in] init_time: Initialize time [sec] + * @param [in] initiali_time_s: Initialize time [sec] */ - void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, double init_time = 0); + void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, + double initiali_time_s = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index a29ed88a2..190f13df2 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -11,7 +11,7 @@ using std::string; Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, - Vector<3> init_position, Vector<3> init_velocity, double init_time) + Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s) : Orbit(celestial_information), ODE<6>(time_step_s), mu_m3_s2(mu_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; @@ -19,7 +19,7 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_i propagation_step_s_ = time_step_s; spacecraft_acceleration_i_m_s2_ *= 0; - Initialize(init_position, init_velocity, init_time); + Initialize(position_i_m, velocity_i_m_s, initiali_time_s); } Rk4OrbitPropagation::~Rk4OrbitPropagation() {} @@ -40,16 +40,16 @@ void Rk4OrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) (void)t; } -void Rk4OrbitPropagation::Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time) { +void Rk4OrbitPropagation::Initialize(Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s) { // state vector [x,y,z,vx,vy,vz] Vector<6> init_state; - init_state[0] = init_position[0]; - init_state[1] = init_position[1]; - init_state[2] = init_position[2]; - init_state[3] = init_velocity[0]; - init_state[4] = init_velocity[1]; - init_state[5] = init_velocity[2]; - setup(init_time, init_state); + init_state[0] = position_i_m[0]; + init_state[1] = position_i_m[1]; + init_state[2] = position_i_m[2]; + init_state[3] = velocity_i_m_s[0]; + init_state[4] = velocity_i_m_s[1]; + init_state[5] = velocity_i_m_s[2]; + setup(initiali_time_s, init_state); // initialize spacecraft_acceleration_i_m_s2_ *= 0; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 7207bfd78..90ed3cfac 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -23,12 +23,12 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] celestial_information: Celestial information * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] time_step_s: Step width [sec] - * @param [in] init_position: Initial value of position in the inertial frame [m] - * @param [in] init_velocity: Initial value of velocity in the inertial frame [m/s] - * @param [in] init_time: Initial time [sec] + * @param [in] position_i_m: Initial value of position in the inertial frame [m] + * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] + * @param [in] initiali_time_s: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, Vector<3> init_position, - Vector<3> init_velocity, double init_time = 0); + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, Vector<3> position_i_m, + Vector<3> velocity_i_m_s, double initiali_time_s = 0); /** * @fn ~Rk4OrbitPropagation * @brief Destructor @@ -62,11 +62,11 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { /** * @fn Initialize * @brief Initialize function - * @param [in] init_position: Initial value of position in the inertial frame [m] - * @param [in] init_velocity: Initial value of velocity in the inertial frame [m/s] - * @param [in] init_time: Initial time [sec] + * @param [in] position_i_m: Initial value of position in the inertial frame [m] + * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] + * @param [in] initiali_time_s: Initial time [sec] */ - void Initialize(Vector<3> init_position, Vector<3> init_velocity, double init_time = 0); + void Initialize(Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s = 0); }; #endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ From d9f8a884d11c60ddbc98fc282e429fb4bce07b99 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:32:20 +0100 Subject: [PATCH 0607/1086] Fix function argument name --- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/orbit/relative_orbit.hpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 14 ++++++-------- src/dynamics/orbit/rk4_orbit_propagation.hpp | 12 ++++++------ 4 files changed, 16 insertions(+), 18 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 25827a635..73c19c145 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -31,7 +31,7 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, RelativeOrbit::~RelativeOrbit() {} void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, - double initiali_time_s) { + double initial_time_s) { relative_position_lvlh_m_ = relative_position_lvlh_m; relative_velocity_lvlh_m_s_ = relative_velocity_lvlh_m_s; @@ -54,7 +54,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l initial_state_[5] = relative_velocity_lvlh_m_s[2]; if (update_method_ == RK4) { - setup(initiali_time_s, initial_state_); + setup(initial_time_s, initial_state_); CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2); } else // update_method_ == STM diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 8a45fff09..1f15aa4dd 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -90,10 +90,10 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] - * @param [in] initiali_time_s: Initialize time [sec] + * @param [in] initial_time_s: Initialize time [sec] */ void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, - double initiali_time_s = 0); + double initial_time_s = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 190f13df2..befe3f427 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -8,10 +8,8 @@ #include #include -using std::string; - Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, - Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s) + libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) : Orbit(celestial_information), ODE<6>(time_step_s), mu_m3_s2(mu_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; @@ -19,12 +17,12 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_i propagation_step_s_ = time_step_s; spacecraft_acceleration_i_m_s2_ *= 0; - Initialize(position_i_m, velocity_i_m_s, initiali_time_s); + Initialize(position_i_m, velocity_i_m_s, initial_time_s); } Rk4OrbitPropagation::~Rk4OrbitPropagation() {} -void Rk4OrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) { +void Rk4OrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { double x = state[0], y = state[1], z = state[2]; double vx = state[3], vy = state[4], vz = state[5]; @@ -40,16 +38,16 @@ void Rk4OrbitPropagation::RHS(double t, const Vector<6>& state, Vector<6>& rhs) (void)t; } -void Rk4OrbitPropagation::Initialize(Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s) { +void Rk4OrbitPropagation::Initialize(Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) { // state vector [x,y,z,vx,vy,vz] - Vector<6> init_state; + libra::Vector<6> init_state; init_state[0] = position_i_m[0]; init_state[1] = position_i_m[1]; init_state[2] = position_i_m[2]; init_state[3] = velocity_i_m_s[0]; init_state[4] = velocity_i_m_s[1]; init_state[5] = velocity_i_m_s[2]; - setup(initiali_time_s, init_state); + setup(initial_time_s, init_state); // initialize spacecraft_acceleration_i_m_s2_ *= 0; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 90ed3cfac..989cb1209 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -25,10 +25,10 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] time_step_s: Step width [sec] * @param [in] position_i_m: Initial value of position in the inertial frame [m] * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] - * @param [in] initiali_time_s: Initial time [sec] + * @param [in] initial_time_s: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, Vector<3> position_i_m, - Vector<3> velocity_i_m_s, double initiali_time_s = 0); + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, libra::Vector<3> position_i_m, + libra::Vector<3> velocity_i_m_s, double initial_time_s = 0); /** * @fn ~Rk4OrbitPropagation * @brief Destructor @@ -43,7 +43,7 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); + virtual void RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); // Override Orbit /** @@ -64,9 +64,9 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @brief Initialize function * @param [in] position_i_m: Initial value of position in the inertial frame [m] * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] - * @param [in] initiali_time_s: Initial time [sec] + * @param [in] initial_time_s: Initial time [sec] */ - void Initialize(Vector<3> position_i_m, Vector<3> velocity_i_m_s, double initiali_time_s = 0); + void Initialize(libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s = 0); }; #endif // S2E_DYNAMICS_ORBIT_RK4_ORBIT_PROPAGATION_HPP_ From 9aa77e1b0b28a6f0bb388b46820f01fb6b49fd2e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:34:19 +0100 Subject: [PATCH 0608/1086] Remove using --- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 7 +++---- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 02c23137d..616db0b3b 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -8,7 +8,6 @@ #include #include #include -using namespace std; Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_time_jd) : Orbit(celestial_information) { @@ -58,8 +57,8 @@ void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) TransformEcefToGeodetic(); } -Vector<3> Sgp4OrbitPropagation::GetESIOmega() { - Vector<3> omega_peri = Vector<3>(); +libra::Vector<3> Sgp4OrbitPropagation::GetESIOmega() { + libra::Vector<3> omega_peri = libra::Vector<3>(); omega_peri[0] = 0.0; omega_peri[1] = 0.0; omega_peri[2] = satrec_.no / 60; @@ -75,7 +74,7 @@ Vector<3> Sgp4OrbitPropagation::GetESIOmega() { double sOMEGA = sin(OMEGA); double si = sin(i); - Matrix<3, 3> PERI2ECI = Matrix<3, 3>(); + libra::Matrix<3, 3> PERI2ECI = libra::Matrix<3, 3>(); PERI2ECI[0][0] = comega * cOMEGA - somega * ci * sOMEGA; PERI2ECI[1][0] = -1.0 * somega * cOMEGA - 1.0 * comega * ci * sOMEGA; PERI2ECI[2][0] = si * sOMEGA; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 9e84bc096..05ff286c8 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -44,7 +44,7 @@ class Sgp4OrbitPropagation : public Orbit { * @brief Calculate and return ? * @note Is this function needed? */ - Vector<3> GetESIOmega(); + libra::Vector<3> GetESIOmega(); private: gravconsttype whichconst_; //!< Gravity constant value type From 80599a615da3d852bb04f176292cf1c04a4af7a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:35:23 +0100 Subject: [PATCH 0609/1086] Remove unused public function --- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 31 ------------------- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 7 ----- 2 files changed, 38 deletions(-) diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 616db0b3b..3c7630be3 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -56,34 +56,3 @@ void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) TransformEciToEcef(); TransformEcefToGeodetic(); } - -libra::Vector<3> Sgp4OrbitPropagation::GetESIOmega() { - libra::Vector<3> omega_peri = libra::Vector<3>(); - omega_peri[0] = 0.0; - omega_peri[1] = 0.0; - omega_peri[2] = satrec_.no / 60; - - double i = satrec_.inclo; // inclination - double OMEGA = satrec_.nodeo; // raan - double omega = satrec_.argpo; // argment of perigee - - double comega = cos(omega); - double cOMEGA = cos(OMEGA); - double ci = cos(i); - double somega = sin(omega); - double sOMEGA = sin(OMEGA); - double si = sin(i); - - libra::Matrix<3, 3> PERI2ECI = libra::Matrix<3, 3>(); - PERI2ECI[0][0] = comega * cOMEGA - somega * ci * sOMEGA; - PERI2ECI[1][0] = -1.0 * somega * cOMEGA - 1.0 * comega * ci * sOMEGA; - PERI2ECI[2][0] = si * sOMEGA; - PERI2ECI[0][1] = comega * sOMEGA + somega * ci * cOMEGA; - PERI2ECI[1][1] = -1.0 * somega * sOMEGA + comega * ci * cOMEGA; - PERI2ECI[2][1] = -1.0 * si * cOMEGA; - PERI2ECI[0][2] = somega * si; - PERI2ECI[1][2] = comega * si; - PERI2ECI[2][2] = ci; - - return PERI2ECI * omega_peri; -} diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 05ff286c8..727391294 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -39,13 +39,6 @@ class Sgp4OrbitPropagation : public Orbit { */ virtual void Propagate(double end_time_s, double current_time_jd); - /** - * @fn GetESIOmega - * @brief Calculate and return ? - * @note Is this function needed? - */ - libra::Vector<3> GetESIOmega(); - private: gravconsttype whichconst_; //!< Gravity constant value type elsetrec satrec_; //!< Structure data for SGP4 library From 28c4ed997cbff741ce7fd11ad1bc9afb4c5104ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:40:00 +0100 Subject: [PATCH 0610/1086] Fix private variables --- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 14 +++++++------- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 3c7630be3..d56059f7b 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -14,17 +14,17 @@ Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial propagate_mode_ = OrbitPropagateMode::kSgp4; if (wgs == 0) { - whichconst_ = wgs72old; + gravity_constant_setting_ = wgs72old; } else if (wgs == 1) { - whichconst_ = wgs72; + gravity_constant_setting_ = wgs72; } else if (wgs == 2) { - whichconst_ = wgs84; + gravity_constant_setting_ = wgs84; } char typerun = 'c', typeinput = 0; double startmfe, stopmfe, deltamin; - twoline2rv(tle1, tle2, typerun, typeinput, whichconst_, startmfe, stopmfe, deltamin, satrec_); + twoline2rv(tle1, tle2, typerun, typeinput, gravity_constant_setting_, startmfe, stopmfe, deltamin, sgp4_data_); spacecraft_acceleration_i_m_s2_ *= 0; @@ -38,15 +38,15 @@ void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) UNUSED(end_time_s); if (!is_calc_enabled_) return; - double elapse_time_min = (current_time_jd - satrec_.jdsatepoch) * (24.0 * 60.0); + double elapse_time_min = (current_time_jd - sgp4_data_.jdsatepoch) * (24.0 * 60.0); double r[3]; double v[3]; - sgp4(whichconst_, satrec_, elapse_time_min, r, v); + sgp4(gravity_constant_setting_, sgp4_data_, elapse_time_min, r, v); // Error in SGP4 - if (satrec_.error > 0) printf("# *** error: time:= %f *** code = %3d\n", satrec_.t, satrec_.error); + if (sgp4_data_.error > 0) printf("# *** error: time:= %f *** code = %3d\n", sgp4_data_.t, sgp4_data_.error); for (int i = 0; i < 3; ++i) { spacecraft_position_i_m_[i] = r[i] * 1000; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 727391294..7b93a70a0 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -40,8 +40,8 @@ class Sgp4OrbitPropagation : public Orbit { virtual void Propagate(double end_time_s, double current_time_jd); private: - gravconsttype whichconst_; //!< Gravity constant value type - elsetrec satrec_; //!< Structure data for SGP4 library + gravconsttype gravity_constant_setting_; //!< Gravity constant value type + elsetrec sgp4_data_; //!< Structure data for SGP4 library const CelestialInformation* celestial_information_; //!< Celestial information }; From e0df5a68fb83e8ec64963df85fa6e23f71f186ed Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:41:31 +0100 Subject: [PATCH 0611/1086] Add const --- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 3 ++- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index d56059f7b..521fc36e0 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -9,7 +9,8 @@ #include #include -Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_time_jd) +Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs, + const double current_time_jd) : Orbit(celestial_information) { propagate_mode_ = OrbitPropagateMode::kSgp4; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 7b93a70a0..80f5d6155 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -28,7 +28,7 @@ class Sgp4OrbitPropagation : public Orbit { * @param [in] wgs: Wold Geodetic System * @param [in] current_time_jd: Current Julian day [day] */ - Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, int wgs, double current_time_jd); + Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs, const double current_time_jd); // Override Orbit /** @@ -37,7 +37,7 @@ class Sgp4OrbitPropagation : public Orbit { * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd); + virtual void Propagate(const double end_time_s, const double current_time_jd); private: gravconsttype gravity_constant_setting_; //!< Gravity constant value type From f9e67f430a4c163251322b2b96394efd98c5fe90 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 20:42:13 +0100 Subject: [PATCH 0612/1086] Fix function argument names --- src/dynamics/orbit/initialize_orbit.cpp | 4 ++-- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 8 ++++---- src/dynamics/orbit/sgp4_orbit_propagation.hpp | 5 +++-- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index c191972ca..d6540fd24 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -36,12 +36,12 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string orbit = new Rk4OrbitPropagation(celestial_information, mu_m3_s2, step_width_s, position_i_m, velocity_i_m_s); } else if (propagate_mode == "SGP4") { // Initialize SGP4 orbit propagator - int wgs = conf.ReadInt(section_, "wgs"); + int wgs_setting = conf.ReadInt(section_, "wgs_setting"); char tle1[80], tle2[80]; conf.ReadChar(section_, "tle1", 80, tle1); conf.ReadChar(section_, "tle2", 80, tle2); - orbit = new Sgp4OrbitPropagation(celestial_information, tle1, tle2, wgs, current_time_jd); + orbit = new Sgp4OrbitPropagation(celestial_information, tle1, tle2, wgs_setting, current_time_jd); } else if (propagate_mode == "RELATIVE") { // initialize orbit for relative dynamics of formation flying RelativeOrbit::RelativeOrbitUpdateMethod update_method = diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 521fc36e0..37580e5a2 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -9,16 +9,16 @@ #include #include -Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs, +Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs_setting, const double current_time_jd) : Orbit(celestial_information) { propagate_mode_ = OrbitPropagateMode::kSgp4; - if (wgs == 0) { + if (wgs_setting == 0) { gravity_constant_setting_ = wgs72old; - } else if (wgs == 1) { + } else if (wgs_setting == 1) { gravity_constant_setting_ = wgs72; - } else if (wgs == 2) { + } else if (wgs_setting == 2) { gravity_constant_setting_ = wgs84; } diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.hpp b/src/dynamics/orbit/sgp4_orbit_propagation.hpp index 80f5d6155..5943ae359 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.hpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.hpp @@ -25,10 +25,11 @@ class Sgp4OrbitPropagation : public Orbit { * @param [in] celestial_information: Celestial information * @param [in] tle1: The first line of TLE * @param [in] tle2: The second line of TLE - * @param [in] wgs: Wold Geodetic System + * @param [in] wgs_setting: Wold Geodetic System * @param [in] current_time_jd: Current Julian day [day] */ - Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs, const double current_time_jd); + Sgp4OrbitPropagation(const CelestialInformation* celestial_information, char* tle1, char* tle2, const int wgs_setting, + const double current_time_jd); // Override Orbit /** From e263a6cf8284b5dc19449db37383d40226b94cb2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 21:39:22 +0100 Subject: [PATCH 0613/1086] Fix local function variables --- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index 37580e5a2..b4c741857 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -22,12 +22,12 @@ Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial gravity_constant_setting_ = wgs84; } - char typerun = 'c', typeinput = 0; - double startmfe, stopmfe, deltamin; + char type_run = 'c', type_input = 0; + double start_mfe, stop_mfe, delta_min; - twoline2rv(tle1, tle2, typerun, typeinput, gravity_constant_setting_, startmfe, stopmfe, deltamin, sgp4_data_); + twoline2rv(tle1, tle2, type_run, type_input, gravity_constant_setting_, start_mfe, stop_mfe, delta_min, sgp4_data_); - spacecraft_acceleration_i_m_s2_ *= 0; + spacecraft_acceleration_i_m_s2_ *= 0.0; // To calculate initial position and velocity is_calc_enabled_ = true; @@ -41,17 +41,17 @@ void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) if (!is_calc_enabled_) return; double elapse_time_min = (current_time_jd - sgp4_data_.jdsatepoch) * (24.0 * 60.0); - double r[3]; - double v[3]; + double position_i_km[3]; + double velocity_i_km_s[3]; - sgp4(gravity_constant_setting_, sgp4_data_, elapse_time_min, r, v); + sgp4(gravity_constant_setting_, sgp4_data_, elapse_time_min, position_i_km, velocity_i_km_s); // Error in SGP4 if (sgp4_data_.error > 0) printf("# *** error: time:= %f *** code = %3d\n", sgp4_data_.t, sgp4_data_.error); for (int i = 0; i < 3; ++i) { - spacecraft_position_i_m_[i] = r[i] * 1000; - spacecraft_velocity_i_m_s_[i] = v[i] * 1000; + spacecraft_position_i_m_[i] = position_i_km[i] * 1000.0; + spacecraft_velocity_i_m_s_[i] = velocity_i_km_s[i] * 1000.0; } TransformEciToEcef(); From b41fc9566cd6af4283ab042ef37316f2d160a8f4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:01:25 +0100 Subject: [PATCH 0614/1086] Fix HipparcosData struct --- src/components/real/mission/telescope.cpp | 28 +++++++++---------- src/components/real/mission/telescope.hpp | 2 +- .../global/hipparcos_catalogue.cpp | 6 ++-- .../global/hipparcos_catalogue.hpp | 27 +++++++++--------- 4 files changed, 31 insertions(+), 32 deletions(-) diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 87de9b002..40bbd30ae 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -43,10 +43,10 @@ Telescope::Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double // Set 0 when t=0 for (size_t i = 0; i < num_of_logged_stars_; i++) { Star star; - star.hipdata.hip_num = -1; - star.hipdata.vmag = -1; - star.hipdata.ra = -1; - star.hipdata.de = -1; + star.hipdata.hipparcos_id = -1; + star.hipdata.visible_magnitude = -1; + star.hipdata.right_ascension_deg = -1; + star.hipdata.declination_deg = -1; star.pos_imgsensor[0] = -1; star.pos_imgsensor[1] = -1; @@ -117,10 +117,10 @@ void Telescope::ObserveStars() { if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { Star star; - star.hipdata.hip_num = hipp_->GetHipparcosId(count); - star.hipdata.vmag = hipp_->GetVisibleMagnitude(count); - star.hipdata.ra = hipp_->GetRA(count); - star.hipdata.de = hipp_->GetDE(count); + star.hipdata.hipparcos_id = hipp_->GetHipparcosId(count); + star.hipdata.visible_magnitude = hipp_->GetVisibleMagnitude(count); + star.hipdata.right_ascension_deg = hipp_->GetRA(count); + star.hipdata.declination_deg = hipp_->GetDE(count); star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; star.pos_imgsensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; @@ -133,10 +133,10 @@ void Telescope::ObserveStars() { if (count >= hipp_->GetCatalogueSize()) { while (star_in_sight.size() < num_of_logged_stars_) { Star star; - star.hipdata.hip_num = -1; - star.hipdata.vmag = -1; - star.hipdata.ra = -1; - star.hipdata.de = -1; + star.hipdata.hipparcos_id = -1; + star.hipdata.visible_magnitude = -1; + star.hipdata.right_ascension_deg = -1; + star.hipdata.declination_deg = -1; star.pos_imgsensor[0] = -1; star.pos_imgsensor[1] = -1; @@ -187,8 +187,8 @@ string Telescope::GetLogValue() const { // When Hipparcos Catalogue was not read, no output of ObserveStars if (hipp_->IsCalcEnabled) { for (size_t i = 0; i < num_of_logged_stars_; i++) { - str_tmp += WriteScalar(star_in_sight[i].hipdata.hip_num); - str_tmp += WriteScalar(star_in_sight[i].hipdata.vmag); + str_tmp += WriteScalar(star_in_sight[i].hipdata.hipparcos_id); + str_tmp += WriteScalar(star_in_sight[i].hipdata.visible_magnitude); str_tmp += WriteVector(star_in_sight[i].pos_imgsensor); } } diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index cb27125ea..794ce6f33 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -20,7 +20,7 @@ * @brief Information of stars in the telescope's field of view */ struct Star { - HipData hipdata; //!< Hipparcos data + HipparcosData hipdata; //!< Hipparcos data libra::Vector<2> pos_imgsensor; //!< Position of image sensor }; diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index 64476cadd..fca3c079d 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -30,16 +30,16 @@ bool HipparcosCatalogue::ReadContents(const std::string& filename, const char de std::string title; ifs >> title; // Skip title while (!ifs.eof()) { - HipData hipdata; + HipparcosData hipdata; std::string line; ifs >> line; std::replace(line.begin(), line.end(), delimiter, ' '); // Convert delimiter as space for stringstream std::istringstream streamline(line); - streamline >> hipdata.hip_num >> hipdata.vmag >> hipdata.ra >> hipdata.de; + streamline >> hipdata.hipparcos_id >> hipdata.visible_magnitude >> hipdata.right_ascension_deg >> hipdata.declination_deg; - if (hipdata.vmag > max_magnitude_) { + if (hipdata.visible_magnitude > max_magnitude_) { return true; } // Don't read stars darker than max_magnitude hipparcos_catalogue_.push_back(hipdata); diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index a94a329b8..79ffca5f2 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -13,16 +13,15 @@ #include "library/math/vector.hpp" /** - *@struct HipData + *@struct HipparcosData *@brief Hipparcos catalogue data */ -struct HipData { - int hip_num; //!< Hipparcos number - double vmag; //!< Visible magnitude - double ra; //!< Right ascension [rad] - double de; //!< Declination [rad] +struct HipparcosData { + int hipparcos_id; //!< Hipparcos number + double visible_magnitude; //!< Visible magnitude + double right_ascension_deg; //!< Right ascension [deg] + double declination_deg; //!< Declination [deg] }; - /** *@class HipparcosCatalogue *@brief Class to calculate star direction with Hipparcos catalogue @@ -59,25 +58,25 @@ class HipparcosCatalogue : public ILoggable { *@brief Return Hipparcos ID of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - int GetHipparcosId(int rank) const { return hipparcos_catalogue_[rank].hip_num; } + int GetHipparcosId(int rank) const { return hipparcos_catalogue_[rank].hipparcos_id; } /** *@fn GetVisibleMagnitude *@brief Return magnitude in visible wave length of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetVisibleMagnitude(int rank) const { return hipparcos_catalogue_[rank].vmag; } + double GetVisibleMagnitude(int rank) const { return hipparcos_catalogue_[rank].visible_magnitude; } /** *@fn GetRA *@brief Return right ascension of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetRA(int rank) const { return hipparcos_catalogue_[rank].ra; } + double GetRA(int rank) const { return hipparcos_catalogue_[rank].right_ascension_deg; } /** *@fn GetDE *@brief Return declination of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetDE(int rank) const { return hipparcos_catalogue_[rank].de; } + double GetDE(int rank) const { return hipparcos_catalogue_[rank].declination_deg; } /** *@fn GetStarDir_i *@brief Return direction vector of a star in the inertial frame @@ -107,9 +106,9 @@ class HipparcosCatalogue : public ILoggable { bool IsCalcEnabled = true; //!< Calculation enable flag private: - std::vector hipparcos_catalogue_; //!< Data base of the read Hipparcos catalogue - double max_magnitude_; //!< Maximum magnitude in the data base - std::string catalogue_path_; //!< Path to Hipparcos catalog file + std::vector hipparcos_catalogue_; //!< Data base of the read Hipparcos catalogue + double max_magnitude_; //!< Maximum magnitude in the data base + std::string catalogue_path_; //!< Path to Hipparcos catalog file }; #endif // S2E_ENVIRONMENT_GLOBAL_HIPPAROCOS_CATALOGUE_HPP_ From 54e892f9aae9c6e39b4ce45cb72c5adcea5a8fa2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:05:03 +0100 Subject: [PATCH 0615/1086] Fix local function --- src/components/real/mission/telescope.cpp | 4 +-- .../global/hipparcos_catalogue.cpp | 25 +++++++++---------- .../global/hipparcos_catalogue.hpp | 8 +++--- 3 files changed, 18 insertions(+), 19 deletions(-) diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 40bbd30ae..a3aafb27c 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -119,8 +119,8 @@ void Telescope::ObserveStars() { Star star; star.hipdata.hipparcos_id = hipp_->GetHipparcosId(count); star.hipdata.visible_magnitude = hipp_->GetVisibleMagnitude(count); - star.hipdata.right_ascension_deg = hipp_->GetRA(count); - star.hipdata.declination_deg = hipp_->GetDE(count); + star.hipdata.right_ascension_deg = hipp_->GetRightAscension_deg(count); + star.hipdata.declination_deg = hipp_->GetDeclination_deg(count); star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; star.pos_imgsensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index fca3c079d..ee82077f6 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -49,26 +49,25 @@ bool HipparcosCatalogue::ReadContents(const std::string& filename, const char de } libra::Vector<3> HipparcosCatalogue::GetStarDirection_i(int rank) const { - libra::Vector<3> position; - // TODO: Check unit of ra and de - double ra = GetRA(rank) * libra::pi / 180; - double de = GetDE(rank) * libra::pi / 180; + libra::Vector<3> direction_i; + double ra_rad = GetRightAscension_deg(rank) * libra::deg_to_rad; + double de_rad = GetDeclination_deg(rank) * libra::deg_to_rad; - position[0] = cos(ra) * cos(de); - position[1] = sin(ra) * cos(de); - position[2] = sin(de); + direction_i[0] = cos(ra_rad) * cos(de_rad); + direction_i[1] = sin(ra_rad) * cos(de_rad); + direction_i[2] = sin(de_rad); - return position; + return direction_i; } libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, Quaternion q_i2b) const { - libra::Vector<3> position_i; - libra::Vector<3> position_b; + libra::Vector<3> direction_i; + libra::Vector<3> direction_b; - position_i = GetStarDirection_i(rank); - position_b = q_i2b.frame_conv(position_i); + direction_i = GetStarDirection_i(rank); + direction_b = q_i2b.frame_conv(direction_i); - return position_b; + return direction_b; } std::string HipparcosCatalogue::GetLogHeader() const { diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 79ffca5f2..cf0d6a313 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -66,17 +66,17 @@ class HipparcosCatalogue : public ILoggable { */ double GetVisibleMagnitude(int rank) const { return hipparcos_catalogue_[rank].visible_magnitude; } /** - *@fn GetRA + *@fn GetRightAscension_deg *@brief Return right ascension of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetRA(int rank) const { return hipparcos_catalogue_[rank].right_ascension_deg; } + double GetRightAscension_deg(int rank) const { return hipparcos_catalogue_[rank].right_ascension_deg; } /** - *@fn GetDE + *@fn GetDeclination_deg *@brief Return declination of a star *@param [in] rank: Rank of star magnitude in read catalogue */ - double GetDE(int rank) const { return hipparcos_catalogue_[rank].declination_deg; } + double GetDeclination_deg(int rank) const { return hipparcos_catalogue_[rank].declination_deg; } /** *@fn GetStarDir_i *@brief Return direction vector of a star in the inertial frame From b1aa385a53bce9b6ad758b65fdd551aca862c4c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:06:47 +0100 Subject: [PATCH 0616/1086] Fix local function --- src/environment/global/hipparcos_catalogue.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index ee82077f6..95a8e2b6b 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -30,19 +30,20 @@ bool HipparcosCatalogue::ReadContents(const std::string& filename, const char de std::string title; ifs >> title; // Skip title while (!ifs.eof()) { - HipparcosData hipdata; + HipparcosData hipparcos_data; std::string line; ifs >> line; std::replace(line.begin(), line.end(), delimiter, ' '); // Convert delimiter as space for stringstream std::istringstream streamline(line); - streamline >> hipdata.hipparcos_id >> hipdata.visible_magnitude >> hipdata.right_ascension_deg >> hipdata.declination_deg; + streamline >> hipparcos_data.hipparcos_id >> hipparcos_data.visible_magnitude >> hipparcos_data.right_ascension_deg >> + hipparcos_data.declination_deg; - if (hipdata.visible_magnitude > max_magnitude_) { + if (hipparcos_data.visible_magnitude > max_magnitude_) { return true; } // Don't read stars darker than max_magnitude - hipparcos_catalogue_.push_back(hipdata); + hipparcos_catalogue_.push_back(hipparcos_data); } return true; From de4ba9662ceba56fb6ca24281cd0aa7e8b690fbb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:08:29 +0100 Subject: [PATCH 0617/1086] Fix function argument name --- src/environment/global/hipparcos_catalogue.cpp | 8 ++++---- src/environment/global/hipparcos_catalogue.hpp | 6 +++--- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index 95a8e2b6b..4e0f0323f 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -18,10 +18,10 @@ HipparcosCatalogue::HipparcosCatalogue(double max_magnitude, std::string catalog HipparcosCatalogue::~HipparcosCatalogue() {} -bool HipparcosCatalogue::ReadContents(const std::string& filename, const char delimiter = ',') { +bool HipparcosCatalogue::ReadContents(const std::string& file_name, const char delimiter = ',') { if (!IsCalcEnabled) return false; - std::ifstream ifs(filename); + std::ifstream ifs(file_name); if (!ifs.is_open()) { std::cerr << "file open error(hip_main.csv)"; return false; @@ -61,12 +61,12 @@ libra::Vector<3> HipparcosCatalogue::GetStarDirection_i(int rank) const { return direction_i; } -libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, Quaternion q_i2b) const { +libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, Quaternion quaternoin_i2b) const { libra::Vector<3> direction_i; libra::Vector<3> direction_b; direction_i = GetStarDirection_i(rank); - direction_b = q_i2b.frame_conv(direction_i); + direction_b = quaternoin_i2b.frame_conv(direction_i); return direction_b; } diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index cf0d6a313..236f9a33f 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -46,7 +46,7 @@ class HipparcosCatalogue : public ILoggable { *@param [in] file_name: Path to Hipparcos catalogue file *@param [in] delimiter: Delimiter for the catalogue file */ - bool ReadContents(const std::string& filename, const char delimiter); + bool ReadContents(const std::string& file_name, const char delimiter); /** *@fn GetCatalogueSize @@ -87,9 +87,9 @@ class HipparcosCatalogue : public ILoggable { *@fn GetStarDir_b *@brief Return direction vector of a star in the body-fixed frame *@param [in] rank: Rank of star magnitude in read catalogue - *@param [in] rank: Quaternion from the inertial frame to the body-fixed frame + *@param [in] quaternoin_i2b: Quaternion from the inertial frame to the body-fixed frame */ - libra::Vector<3> GetStarDirection_b(int rank, Quaternion q_i2b) const; + libra::Vector<3> GetStarDirection_b(int rank, Quaternion quaternoin_i2b) const; // Override ILoggable /** From 36318b19824e12a6b694ab47757f0ed3d96c36ae Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:15:35 +0100 Subject: [PATCH 0618/1086] Fix private variables --- src/library/geodesy/geodetic_position.cpp | 24 +++++++++++------------ src/library/geodesy/geodetic_position.hpp | 4 ++-- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 4f0478f5b..828314d90 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -70,16 +70,16 @@ libra::Vector<3> GeodeticPosition::CalcEcefPosition() const { } void GeodeticPosition::CalcQuaternionXcxfToLtc() { - libra::Matrix<3, 3> trans_mat_xcxf_to_ltc; - trans_mat_xcxf_to_ltc[0][0] = -sin(longitude_rad_); - trans_mat_xcxf_to_ltc[0][1] = cos(longitude_rad_); - trans_mat_xcxf_to_ltc[0][2] = 0; - trans_mat_xcxf_to_ltc[1][0] = -sin(latitude_rad_) * cos(longitude_rad_); - trans_mat_xcxf_to_ltc[1][1] = -sin(latitude_rad_) * sin(longitude_rad_); - trans_mat_xcxf_to_ltc[1][2] = cos(latitude_rad_); - trans_mat_xcxf_to_ltc[2][0] = cos(latitude_rad_) * cos(longitude_rad_); - trans_mat_xcxf_to_ltc[2][1] = cos(latitude_rad_) * sin(longitude_rad_); - trans_mat_xcxf_to_ltc[2][2] = sin(latitude_rad_); - - q_xcxf_to_ltc_ = q_xcxf_to_ltc_.fromDCM(trans_mat_xcxf_to_ltc); + libra::Matrix<3, 3> dcm_xcxf_to_ltc; + dcm_xcxf_to_ltc[0][0] = -sin(longitude_rad_); + dcm_xcxf_to_ltc[0][1] = cos(longitude_rad_); + dcm_xcxf_to_ltc[0][2] = 0; + dcm_xcxf_to_ltc[1][0] = -sin(latitude_rad_) * cos(longitude_rad_); + dcm_xcxf_to_ltc[1][1] = -sin(latitude_rad_) * sin(longitude_rad_); + dcm_xcxf_to_ltc[1][2] = cos(latitude_rad_); + dcm_xcxf_to_ltc[2][0] = cos(latitude_rad_) * cos(longitude_rad_); + dcm_xcxf_to_ltc[2][1] = cos(latitude_rad_) * sin(longitude_rad_); + dcm_xcxf_to_ltc[2][2] = sin(latitude_rad_); + + quaternion_xcxf_to_ltc_ = quaternion_xcxf_to_ltc_.fromDCM(dcm_xcxf_to_ltc); } diff --git a/src/library/geodesy/geodetic_position.hpp b/src/library/geodesy/geodetic_position.hpp index 09da97ebc..bdef289e3 100644 --- a/src/library/geodesy/geodetic_position.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -62,14 +62,14 @@ class GeodeticPosition { * @fn GetQuaternionXcxfToLtc * @brief Conversion quaternion from XCXF (e.g. ECEF) to LTC frame */ - inline libra::Quaternion GetQuaternionXcxfToLtc() const { return q_xcxf_to_ltc_; } + inline libra::Quaternion GetQuaternionXcxfToLtc() const { return quaternion_xcxf_to_ltc_; } private: double latitude_rad_; //!< Latitude [rad] South: -π/2 to 0, North: 0 to π/2 double longitude_rad_; //!< Longitude [rad] East: 0 to π, West: 2π to π (i.e., defined as 0 to 2π [rad] east of the Greenwich meridian) double altitude_m_; //!< Altitude [m] - libra::Quaternion q_xcxf_to_ltc_; //!< Conversion quaternion from XCXF (e.g. ECEF) to LTC (Local Topographic Coordinate) + libra::Quaternion quaternion_xcxf_to_ltc_; //!< Conversion quaternion from XCXF (e.g. ECEF) to LTC (Local Topographic Coordinate) /** * @fn CalcQuaternionXcxfToLtc From 97cfb4151e9c900a1c0d3b6db5c7d16068f210b4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:16:54 +0100 Subject: [PATCH 0619/1086] Fix local function variables --- src/library/geodesy/geodetic_position.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index 828314d90..b3ec4eece 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -58,13 +58,13 @@ libra::Vector<3> GeodeticPosition::CalcEcefPosition() const { double theta = FMod2p(longitude_rad_); double e2 = flattening * (2.0 - flattening); - double c = 1 / sqrt(1.0 - e2 * sin(latitude_rad_) * sin(latitude_rad_)); - double N = c * earth_radius_m; + double c = 1.0 / sqrt(1.0 - e2 * sin(latitude_rad_) * sin(latitude_rad_)); + double n = c * earth_radius_m; libra::Vector<3> pos_ecef_m; - pos_ecef_m(0) = (N + altitude_m_) * cos(latitude_rad_) * cos(theta); - pos_ecef_m(1) = (N + altitude_m_) * cos(latitude_rad_) * sin(theta); - pos_ecef_m(2) = (N * (1 - e2) + altitude_m_) * sin(latitude_rad_); + pos_ecef_m(0) = (n + altitude_m_) * cos(latitude_rad_) * cos(theta); + pos_ecef_m(1) = (n + altitude_m_) * cos(latitude_rad_) * sin(theta); + pos_ecef_m(2) = (n * (1.0 - e2) + altitude_m_) * sin(latitude_rad_); return pos_ecef_m; } From 167405d93044e9e0c40276d0e1662a5ed7ccfef5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:18:45 +0100 Subject: [PATCH 0620/1086] Fix public function name --- src/dynamics/orbit/orbit.cpp | 6 +++--- src/dynamics/orbit/orbit.hpp | 12 ++++++------ src/environment/local/atmosphere.cpp | 8 ++++---- src/environment/local/geomagnetic_field.cpp | 6 +++--- src/library/geodesy/geodetic_position.hpp | 12 ++++++------ 5 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 58e2bb9e9..0c59d0b6b 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -75,9 +75,9 @@ std::string Orbit::GetLogValue() const { str_tmp += WriteVector(spacecraft_velocity_i_m_s_, 10); str_tmp += WriteVector(spacecraft_velocity_b_m_s_, 10); str_tmp += WriteVector(spacecraft_acceleration_i_m_s2_, 10); - str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLat_rad()); - str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLon_rad()); - str_tmp += WriteScalar(spacecraft_geodetic_position_.GetAlt_m()); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLatitude_rad()); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetLongitude_rad()); + str_tmp += WriteScalar(spacecraft_geodetic_position_.GetAltitude_m()); return str_tmp; } diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 1178be861..53b6952a6 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -116,14 +116,14 @@ class Orbit : public ILoggable { inline GeodeticPosition GetGeodeticPosition() const { return spacecraft_geodetic_position_; } // TODO delete the following functions - inline double GetLat_rad() const { return spacecraft_geodetic_position_.GetLat_rad(); } - inline double GetLon_rad() const { return spacecraft_geodetic_position_.GetLon_rad(); } - inline double GetAlt_m() const { return spacecraft_geodetic_position_.GetAlt_m(); } + inline double GetLatitude_rad() const { return spacecraft_geodetic_position_.GetLatitude_rad(); } + inline double GetLongitude_rad() const { return spacecraft_geodetic_position_.GetLongitude_rad(); } + inline double GetAltitude_m() const { return spacecraft_geodetic_position_.GetAltitude_m(); } inline libra::Vector<3> GetLatLonAlt() const { libra::Vector<3> vec; - vec(0) = spacecraft_geodetic_position_.GetLat_rad(); - vec(1) = spacecraft_geodetic_position_.GetLon_rad(); - vec(2) = spacecraft_geodetic_position_.GetAlt_m(); + vec(0) = spacecraft_geodetic_position_.GetLatitude_rad(); + vec(1) = spacecraft_geodetic_position_.GetLongitude_rad(); + vec(2) = spacecraft_geodetic_position_.GetAltitude_m(); return vec; } diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index d8f92fd7c..62c809082 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -41,7 +41,7 @@ double Atmosphere::CalcAirDensity_kg_m3(const double decimal_year, const double if (!IsCalcEnabled) return 0; if (model_ == "STANDARD") { - double altitude_m = position.GetAlt_m(); + double altitude_m = position.GetAltitude_m(); air_density_kg_m3_ = CalcStandard(altitude_m); } else if (model_ == "NRLMSISE00") // NRLMSISE00 model { @@ -56,9 +56,9 @@ double Atmosphere::CalcAirDensity_kg_m3(const double decimal_year, const double } } - double lat_rad = position.GetLat_rad(); - double lon_rad = position.GetLon_rad(); - double alt_m = position.GetAlt_m(); + double lat_rad = position.GetLatitude_rad(); + double lon_rad = position.GetLongitude_rad(); + double alt_m = position.GetAltitude_m(); air_density_kg_m3_ = CalcNRLMSISE00(decimal_year, lat_rad, lon_rad, alt_m, space_weather_table_, is_manual_param_used_, manual_daily_f107_, manual_average_f107_, manual_ap_); } else { diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 5aec7f26c..6f36272b7 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -26,9 +26,9 @@ void GeomagneticField::CalcMagneticField(const double decimal_year, const double const Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; - const double lat_rad = position.GetLat_rad(); - const double lon_rad = position.GetLon_rad(); - const double alt_m = position.GetAlt_m(); + const double lat_rad = position.GetLatitude_rad(); + const double lon_rad = position.GetLongitude_rad(); + const double alt_m = position.GetAltitude_m(); double magnetic_field_array_i_nT[3]; IgrfCalc(decimal_year, lat_rad, lon_rad, alt_m, sidereal_day, magnetic_field_array_i_nT); diff --git a/src/library/geodesy/geodetic_position.hpp b/src/library/geodesy/geodetic_position.hpp index bdef289e3..2b6c68eec 100644 --- a/src/library/geodesy/geodetic_position.hpp +++ b/src/library/geodesy/geodetic_position.hpp @@ -44,20 +44,20 @@ class GeodeticPosition { // Getter /** - * @fn GetLat_rad + * @fn GetLatitude_rad * @brief Return latitude [rad] */ - inline double GetLat_rad() const { return latitude_rad_; } + inline double GetLatitude_rad() const { return latitude_rad_; } /** - * @fn GetLon_rad + * @fn GetLongitude_rad * @brief Return longitude [rad] */ - inline double GetLon_rad() const { return longitude_rad_; } + inline double GetLongitude_rad() const { return longitude_rad_; } /** - * @fn GetAlt_m + * @fn GetAltitude_m * @brief Return altitude [m] */ - inline double GetAlt_m() const { return altitude_m_; } + inline double GetAltitude_m() const { return altitude_m_; } /** * @fn GetQuaternionXcxfToLtc * @brief Conversion quaternion from XCXF (e.g. ECEF) to LTC frame From d7793f1e4488bf484df812196e41799b15b28a81 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Feb 2023 22:24:24 +0100 Subject: [PATCH 0621/1086] Remove using --- .../initialize/initialize_file_access.cpp | 64 +++++++++---------- .../initialize/initialize_file_access.hpp | 9 +-- 2 files changed, 34 insertions(+), 39 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index 5624227e6..09016675c 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -11,15 +11,13 @@ #include #include -using namespace std; - #ifdef WIN32 IniAccess::IniAccess(string path) : file_path_(path) { // strcpy_s(strPath_, (size_t)_countof(strPath_), file_path_.c_str()); strncpy(strPath_, file_path_.c_str(), MAX_PATH); } #else -IniAccess::IniAccess(string path) : file_path_(path), reader(path) { +IniAccess::IniAccess(std::string path) : file_path_(path), reader(path) { strncpy(strPath_, file_path_.c_str(), MAX_PATH); std::string ext = ".ini"; @@ -28,8 +26,8 @@ IniAccess::IniAccess(string path) : file_path_(path), reader(path) { return; } if (reader.ParseError() != 0) { - cerr << "Error reading INI file : " << path << endl; - cerr << "\t error code: " << reader.ParseError() << endl; + std::cerr << "Error reading INI file : " << path << std::endl; + std::cerr << "\t error code: " << reader.ParseError() << std::endl; throw std::runtime_error("Error reading INI file"); } } @@ -79,25 +77,25 @@ bool IniAccess::ReadBoolean(const char* section_name, const char* key_name) { void IniAccess::ReadDoubleArray(const char* section_name, const char* key_name, int id, int num, double* data) { for (int i = 0; i < num; i++) { - stringstream c_name; + std::stringstream c_name; c_name << key_name << id << "(" << i << ")"; data[i] = ReadDouble(section_name, c_name.str().c_str()); } } -void IniAccess::ReadQuaternion(const char* section_name, const char* key_name, Quaternion& data) { - Quaternion temp; +void IniAccess::ReadQuaternion(const char* section_name, const char* key_name, libra::Quaternion& data) { + libra::Quaternion temp; double norm = 0.0; for (int i = 0; i < 4; i++) { // Read Quaternion as new format - stringstream c_name; + std::stringstream c_name; c_name << key_name << "_(" << i << ")"; temp[i] = ReadDouble(section_name, c_name.str().c_str()); norm += temp[i] * temp[i]; } if (norm == 0.0) { // If it is not new format, try to read old format for (int i = 0; i < 4; i++) { - stringstream c_name; + std::stringstream c_name; c_name << key_name << "(" << i << ")"; data[i] = ReadDouble(section_name, c_name.str().c_str()); } @@ -113,36 +111,36 @@ void IniAccess::ReadChar(const char* section_name, const char* key_name, int siz #ifdef WIN32 GetPrivateProfileStringA(section_name, key_name, 0, data, size, strPath_); #else - string sdata = ReadString(section_name, key_name); + std::string sdata = ReadString(section_name, key_name); strncpy(data, sdata.c_str(), size); #endif } -string IniAccess::ReadString(const char* section_name, const char* key_name) { +std::string IniAccess::ReadString(const char* section_name, const char* key_name) { #ifdef WIN32 char temp[1024]; ReadChar(section_name, key_name, 1024, temp); return string(temp); #else - string value = reader.GetString(section_name, key_name, "NULL"); + std::string value = reader.GetString(section_name, key_name, "NULL"); return value; #endif } bool IniAccess::ReadEnable(const char* section_name, const char* key_name) { - string enablestr = ReadString(section_name, key_name); + std::string enablestr = ReadString(section_name, key_name); if (enablestr.compare("ENABLE") == 0) return true; if (enablestr.compare("1") == 0) return true; return false; } -vector IniAccess::ReadStrVector(const char* section_name, const char* key_name) { +std::vector IniAccess::ReadStrVector(const char* section_name, const char* key_name) { const static unsigned int buf_size = 1024; - vector data; + std::vector data; char temp[buf_size]; unsigned int i = 0; while (true) { - stringstream c_name; + std::stringstream c_name; c_name << key_name << "(" << i << ")"; ReadChar(section_name, c_name.str().c_str(), buf_size, temp); #ifdef WIN32 @@ -159,46 +157,46 @@ vector IniAccess::ReadStrVector(const char* section_name, const char* ke return data; } -vector IniAccess::Split(string& input, char delimiter) { - istringstream stream(input); - string field; - vector result; +std::vector IniAccess::Split(std::string& input, char delimiter) { + std::istringstream stream(input); + std::string field; + std::vector result; while (getline(stream, field, delimiter)) { result.push_back(field); } return result; } -void IniAccess::ReadCsvDouble(vector>& doublevec, int node_num) { - ifstream ifs(strPath_); +void IniAccess::ReadCsvDouble(std::vector>& doublevec, int node_num) { + std::ifstream ifs(strPath_); if (!ifs.is_open()) { - cerr << "file open error. filename = " << strPath_ << std::endl; + std::cerr << "file open error. filename = " << strPath_ << std::endl; } - string line; + std::string line; int line_num = 0; doublevec.reserve(node_num); while (getline(ifs, line)) { - vector strvec = Split(line, ','); - vector tempdoublevec; + std::vector strvec = Split(line, ','); + std::vector tempdoublevec; tempdoublevec.reserve(node_num); for (size_t i = 0; i < strvec.size(); i++) { - tempdoublevec.push_back(stod(strvec.at(i))); + tempdoublevec.push_back(std::stod(strvec.at(i))); } doublevec.push_back(tempdoublevec); line_num++; } } -void IniAccess::ReadCsvString(vector>& stringvec, int node_num) { - ifstream ifs(strPath_); +void IniAccess::ReadCsvString(std::vector>& stringvec, int node_num) { + std::ifstream ifs(strPath_); if (!ifs.is_open()) { - cerr << "file open error. filename = " << strPath_ << std::endl; + std::cerr << "file open error. filename = " << strPath_ << std::endl; } - string line; + std::string line; int line_num = 0; stringvec.reserve(node_num); while (getline(ifs, line)) { - vector tempstrvec = Split(line, ','); + std::vector tempstrvec = Split(line, ','); tempstrvec.reserve(node_num); stringvec.push_back(tempstrvec); line_num++; diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index a524f0f39..aa6e6ffca 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -25,9 +25,6 @@ #undef MAX_PATH #define MAX_PATH 1024 -using libra::Quaternion; -using libra::Vector; - /** * @class IniAccess * @brief Class to read and get parameters for the `ini` format file @@ -91,7 +88,7 @@ class IniAccess { * @param[out] data: Read vector type data */ template - void ReadVector(const char* section_name, const char* key_name, Vector& data); + void ReadVector(const char* section_name, const char* key_name, libra::Vector& data); /** * @fn ReadStrVector * @brief Read list of string type @@ -107,7 +104,7 @@ class IniAccess { * @param[in] key_name: Key name * @param[out] data: Read quaternion data */ - void ReadQuaternion(const char* section_name, const char* key_name, Quaternion& data); + void ReadQuaternion(const char* section_name, const char* key_name, libra::Quaternion& data); /** * @fn ReadChar * @brief Read characters data @@ -161,7 +158,7 @@ class IniAccess { }; template -void IniAccess::ReadVector(const char* section_name, const char* key_name, Vector& data) { +void IniAccess::ReadVector(const char* section_name, const char* key_name, libra::Vector& data) { for (size_t i = 0; i < NumElement; i++) { std::stringstream c_name; c_name << key_name << "(" << i << ")"; From a01af8aacecee8d94cb8c64ed23d02c0bbab2609 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 13:41:32 +0100 Subject: [PATCH 0622/1086] Fix public MAX_PATH to be private --- src/library/initialize/initialize_file_access.cpp | 4 ++-- src/library/initialize/initialize_file_access.hpp | 10 ++++------ 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index 09016675c..89b884e7a 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -14,11 +14,11 @@ #ifdef WIN32 IniAccess::IniAccess(string path) : file_path_(path) { // strcpy_s(strPath_, (size_t)_countof(strPath_), file_path_.c_str()); - strncpy(strPath_, file_path_.c_str(), MAX_PATH); + strncpy(strPath_, file_path_.c_str(), kMaxCharLength); } #else IniAccess::IniAccess(std::string path) : file_path_(path), reader(path) { - strncpy(strPath_, file_path_.c_str(), MAX_PATH); + strncpy(strPath_, file_path_.c_str(), kMaxCharLength); std::string ext = ".ini"; if (path.size() < 4 || !std::equal(std::rbegin(ext), std::rend(ext), std::rbegin(path))) { diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index aa6e6ffca..0a859c994 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -22,18 +22,16 @@ #include #include -#undef MAX_PATH -#define MAX_PATH 1024 - /** * @class IniAccess * @brief Class to read and get parameters for the `ini` format file */ class IniAccess { private: - std::string file_path_; //!< File path in string - char strPath_[MAX_PATH]; //!< File path in char - char strText_[1024]; //!< buffer + static const size_t kMaxCharLength = 1024; + std::string file_path_; //!< File path in string + char strPath_[kMaxCharLength]; //!< File path in char + char strText_[kMaxCharLength]; //!< buffer #ifndef WIN32 INIReader reader; //!< ini reader #endif From 6b295be821616cf06fe0d638ce8d93a64c2d0e52 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 13:53:43 +0100 Subject: [PATCH 0623/1086] Fix private variables name --- .../initialize/initialize_file_access.cpp | 42 +++++++++---------- .../initialize/initialize_file_access.hpp | 8 ++-- 2 files changed, 25 insertions(+), 25 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index 89b884e7a..b96a7497e 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -13,21 +13,21 @@ #ifdef WIN32 IniAccess::IniAccess(string path) : file_path_(path) { - // strcpy_s(strPath_, (size_t)_countof(strPath_), file_path_.c_str()); - strncpy(strPath_, file_path_.c_str(), kMaxCharLength); + // strcpy_s(file_path_char_, (size_t)_countof(file_path_char_), file_path_.c_str()); + strncpy(file_path_char_, file_path_.c_str(), kMaxCharLength); } #else -IniAccess::IniAccess(std::string path) : file_path_(path), reader(path) { - strncpy(strPath_, file_path_.c_str(), kMaxCharLength); +IniAccess::IniAccess(std::string path) : file_path_(path), ini_reader_(path) { + strncpy(file_path_char_, file_path_.c_str(), kMaxCharLength); std::string ext = ".ini"; if (path.size() < 4 || !std::equal(std::rbegin(ext), std::rend(ext), std::rbegin(path))) { // this is not ini file(csv) return; } - if (reader.ParseError() != 0) { + if (ini_reader_.ParseError() != 0) { std::cerr << "Error reading INI file : " << path << std::endl; - std::cerr << "\t error code: " << reader.ParseError() << std::endl; + std::cerr << "\t error code: " << ini_reader_.ParseError() << std::endl; throw std::runtime_error("Error reading INI file"); } } @@ -38,15 +38,15 @@ double IniAccess::ReadDouble(const char* section_name, const char* key_name) { stringstream value; double temp = 0; - GetPrivateProfileStringA(section_name, key_name, 0, strText_, 1024, strPath_); + GetPrivateProfileStringA(section_name, key_name, 0, text_buffer_, 1024, file_path_char_); - value << strText_; // input string - value >> temp; // return as double - // cout << strText_; + value << text_buffer_; // input string + value >> temp; // return as double + // cout << text_buffer_; return temp; #else - return reader.GetReal(section_name, key_name, 0); + return ini_reader_.GetReal(section_name, key_name, 0); #endif } @@ -54,24 +54,24 @@ int IniAccess::ReadInt(const char* section_name, const char* key_name) { #ifdef WIN32 int temp; - temp = GetPrivateProfileIntA(section_name, key_name, 0, strPath_); + temp = GetPrivateProfileIntA(section_name, key_name, 0, file_path_char_); return temp; #else - return (int)reader.GetInteger(section_name, key_name, 0); + return (int)ini_reader_.GetInteger(section_name, key_name, 0); #endif } bool IniAccess::ReadBoolean(const char* section_name, const char* key_name) { #ifdef WIN32 int temp; - temp = GetPrivateProfileIntA(section_name, key_name, 0, strPath_); + temp = GetPrivateProfileIntA(section_name, key_name, 0, file_path_char_); if (temp > 0) { return true; } return false; #else - return reader.GetBoolean(section_name, key_name, false); + return ini_reader_.GetBoolean(section_name, key_name, false); #endif } @@ -109,7 +109,7 @@ void IniAccess::ReadQuaternion(const char* section_name, const char* key_name, l void IniAccess::ReadChar(const char* section_name, const char* key_name, int size, char* data) { #ifdef WIN32 - GetPrivateProfileStringA(section_name, key_name, 0, data, size, strPath_); + GetPrivateProfileStringA(section_name, key_name, 0, data, size, file_path_char_); #else std::string sdata = ReadString(section_name, key_name); strncpy(data, sdata.c_str(), size); @@ -122,7 +122,7 @@ std::string IniAccess::ReadString(const char* section_name, const char* key_name ReadChar(section_name, key_name, 1024, temp); return string(temp); #else - std::string value = reader.GetString(section_name, key_name, "NULL"); + std::string value = ini_reader_.GetString(section_name, key_name, "NULL"); return value; #endif } @@ -168,9 +168,9 @@ std::vector IniAccess::Split(std::string& input, char delimiter) { } void IniAccess::ReadCsvDouble(std::vector>& doublevec, int node_num) { - std::ifstream ifs(strPath_); + std::ifstream ifs(file_path_char_); if (!ifs.is_open()) { - std::cerr << "file open error. filename = " << strPath_ << std::endl; + std::cerr << "file open error. filename = " << file_path_char_ << std::endl; } std::string line; int line_num = 0; @@ -188,9 +188,9 @@ void IniAccess::ReadCsvDouble(std::vector>& doublevec, int n } void IniAccess::ReadCsvString(std::vector>& stringvec, int node_num) { - std::ifstream ifs(strPath_); + std::ifstream ifs(file_path_char_); if (!ifs.is_open()) { - std::cerr << "file open error. filename = " << strPath_ << std::endl; + std::cerr << "file open error. filename = " << file_path_char_ << std::endl; } std::string line; int line_num = 0; diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index 0a859c994..e959c6a77 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -29,11 +29,11 @@ class IniAccess { private: static const size_t kMaxCharLength = 1024; - std::string file_path_; //!< File path in string - char strPath_[kMaxCharLength]; //!< File path in char - char strText_[kMaxCharLength]; //!< buffer + std::string file_path_; //!< File path in string + char file_path_char_[kMaxCharLength]; //!< File path in char + char text_buffer_[kMaxCharLength]; //!< buffer #ifndef WIN32 - INIReader reader; //!< ini reader + INIReader ini_reader_; //!< ini ini_reader_ #endif public: From 632d5a97444170fef8d97bf5196cd7eab5402766 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:04:43 +0100 Subject: [PATCH 0624/1086] Fix function argument --- .../initialize/initialize_file_access.cpp | 26 +++++++++---------- .../initialize/initialize_file_access.hpp | 17 ++++++------ 2 files changed, 22 insertions(+), 21 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index b96a7497e..5546f1a67 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -12,21 +12,21 @@ #include #ifdef WIN32 -IniAccess::IniAccess(string path) : file_path_(path) { +IniAccess::IniAccess(const std::string file_path) : file_path_(file_path) { // strcpy_s(file_path_char_, (size_t)_countof(file_path_char_), file_path_.c_str()); strncpy(file_path_char_, file_path_.c_str(), kMaxCharLength); } #else -IniAccess::IniAccess(std::string path) : file_path_(path), ini_reader_(path) { +IniAccess::IniAccess(const std::string file_path) : file_path_(file_path), ini_reader_(file_path) { strncpy(file_path_char_, file_path_.c_str(), kMaxCharLength); std::string ext = ".ini"; - if (path.size() < 4 || !std::equal(std::rbegin(ext), std::rend(ext), std::rbegin(path))) { + if (file_path_.size() < 4 || !std::equal(std::rbegin(ext), std::rend(ext), std::rbegin(file_path_))) { // this is not ini file(csv) return; } if (ini_reader_.ParseError() != 0) { - std::cerr << "Error reading INI file : " << path << std::endl; + std::cerr << "Error reading INI file : " << file_path_ << std::endl; std::cerr << "\t error code: " << ini_reader_.ParseError() << std::endl; throw std::runtime_error("Error reading INI file"); } @@ -75,7 +75,7 @@ bool IniAccess::ReadBoolean(const char* section_name, const char* key_name) { #endif } -void IniAccess::ReadDoubleArray(const char* section_name, const char* key_name, int id, int num, double* data) { +void IniAccess::ReadDoubleArray(const char* section_name, const char* key_name, const int id, const int num, double* data) { for (int i = 0; i < num; i++) { std::stringstream c_name; c_name << key_name << id << "(" << i << ")"; @@ -107,7 +107,7 @@ void IniAccess::ReadQuaternion(const char* section_name, const char* key_name, l } } -void IniAccess::ReadChar(const char* section_name, const char* key_name, int size, char* data) { +void IniAccess::ReadChar(const char* section_name, const char* key_name, const int size, char* data) { #ifdef WIN32 GetPrivateProfileStringA(section_name, key_name, 0, data, size, file_path_char_); #else @@ -157,7 +157,7 @@ std::vector IniAccess::ReadStrVector(const char* section_name, cons return data; } -std::vector IniAccess::Split(std::string& input, char delimiter) { +std::vector IniAccess::Split(const std::string& input, const char delimiter) { std::istringstream stream(input); std::string field; std::vector result; @@ -167,14 +167,14 @@ std::vector IniAccess::Split(std::string& input, char delimiter) { return result; } -void IniAccess::ReadCsvDouble(std::vector>& doublevec, int node_num) { +void IniAccess::ReadCsvDouble(std::vector>& output_value, const int node_num) { std::ifstream ifs(file_path_char_); if (!ifs.is_open()) { std::cerr << "file open error. filename = " << file_path_char_ << std::endl; } std::string line; int line_num = 0; - doublevec.reserve(node_num); + output_value.reserve(node_num); while (getline(ifs, line)) { std::vector strvec = Split(line, ','); std::vector tempdoublevec; @@ -182,23 +182,23 @@ void IniAccess::ReadCsvDouble(std::vector>& doublevec, int n for (size_t i = 0; i < strvec.size(); i++) { tempdoublevec.push_back(std::stod(strvec.at(i))); } - doublevec.push_back(tempdoublevec); + output_value.push_back(tempdoublevec); line_num++; } } -void IniAccess::ReadCsvString(std::vector>& stringvec, int node_num) { +void IniAccess::ReadCsvString(std::vector>& output_value, const int node_num) { std::ifstream ifs(file_path_char_); if (!ifs.is_open()) { std::cerr << "file open error. filename = " << file_path_char_ << std::endl; } std::string line; int line_num = 0; - stringvec.reserve(node_num); + output_value.reserve(node_num); while (getline(ifs, line)) { std::vector tempstrvec = Split(line, ','); tempstrvec.reserve(node_num); - stringvec.push_back(tempstrvec); + output_value.push_back(tempstrvec); line_num++; } } diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index e959c6a77..6d08dfa42 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -40,8 +40,9 @@ class IniAccess { /** * @fn IniAccess * @brief Constructor + * @param[in] file_path: File path of ini file */ - IniAccess(std::string path); + IniAccess(const std::string file_path); // Read functions /** @@ -77,7 +78,7 @@ class IniAccess { * @param[in] num: Number of elements of the array * @param[out] data: Read array data */ - void ReadDoubleArray(const char* section_name, const char* key_name, int id, int num, double* data); + void ReadDoubleArray(const char* section_name, const char* key_name, const int id, const int num, double* data); /** * @fn ReadVector * @brief Read Vector type number @@ -111,7 +112,7 @@ class IniAccess { * @param [in] size: Length of the character * @param[out] data: Read character data */ - void ReadChar(const char* section_name, const char* key_name, int size, char* data); + void ReadChar(const char* section_name, const char* key_name, const int size, char* data); /** * @fn ReadString * @brief Read string data @@ -138,21 +139,21 @@ class IniAccess { * @param[in] delimiter: Delimiter to split the string * @return List of string splitted by the delimiter */ - std::vector Split(std::string& input, char delimiter); + std::vector Split(const std::string& input, const char delimiter); /** * @fn ReadCsvDouble * @brief Read matrix value in CSV file - * @param[out] doublevec: Read double matrix value + * @param[out] output_value: Read double matrix value * @param[in] node_num: Number of node. When reading n * m matrix, please substitute bigger number. */ - void ReadCsvDouble(std::vector>& doublevec, int node_num); + void ReadCsvDouble(std::vector>& output_value, const int node_num); /** * @fn ReadCsvString * @brief Read matrix of string in CSV file - * @param[out] stringvec: Read matrix of string + * @param[out] output_value: Read matrix of string * @param[in] node_num: Number of node. When reading n * m matrix, please substitute bigger number. */ - void ReadCsvString(std::vector>& stringvec, int node_num); + void ReadCsvString(std::vector>& output_value, const int node_num); }; template From cefc620b2182b14dcd196e63e7192d5f8f9f1379 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:05:42 +0100 Subject: [PATCH 0625/1086] Move private position --- .../initialize/initialize_file_access.hpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index 6d08dfa42..ecde4664b 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -27,15 +27,6 @@ * @brief Class to read and get parameters for the `ini` format file */ class IniAccess { - private: - static const size_t kMaxCharLength = 1024; - std::string file_path_; //!< File path in string - char file_path_char_[kMaxCharLength]; //!< File path in char - char text_buffer_[kMaxCharLength]; //!< buffer -#ifndef WIN32 - INIReader ini_reader_; //!< ini ini_reader_ -#endif - public: /** * @fn IniAccess @@ -154,6 +145,15 @@ class IniAccess { * @param[in] node_num: Number of node. When reading n * m matrix, please substitute bigger number. */ void ReadCsvString(std::vector>& output_value, const int node_num); + + private: + static const size_t kMaxCharLength = 1024; + std::string file_path_; //!< File path in string + char file_path_char_[kMaxCharLength]; //!< File path in char + char text_buffer_[kMaxCharLength]; //!< buffer +#ifndef WIN32 + INIReader ini_reader_; //!< ini ini_reader_ +#endif }; template From 92c6abe9459403dd45ce72368e38191c7bd47b8e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:19:35 +0100 Subject: [PATCH 0626/1086] Fix local function variables --- .../initialize/initialize_file_access.cpp | 57 +++++++++---------- .../initialize/initialize_file_access.hpp | 1 + 2 files changed, 29 insertions(+), 29 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index 5546f1a67..22a2dbbbe 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -38,7 +38,7 @@ double IniAccess::ReadDouble(const char* section_name, const char* key_name) { stringstream value; double temp = 0; - GetPrivateProfileStringA(section_name, key_name, 0, text_buffer_, 1024, file_path_char_); + GetPrivateProfileStringA(section_name, key_name, 0, text_buffer_, kMaxCharLength, file_path_char_); value << text_buffer_; // input string value >> temp; // return as double @@ -77,9 +77,9 @@ bool IniAccess::ReadBoolean(const char* section_name, const char* key_name) { void IniAccess::ReadDoubleArray(const char* section_name, const char* key_name, const int id, const int num, double* data) { for (int i = 0; i < num; i++) { - std::stringstream c_name; - c_name << key_name << id << "(" << i << ")"; - data[i] = ReadDouble(section_name, c_name.str().c_str()); + std::stringstream edited_key_name; + edited_key_name << key_name << id << "(" << i << ")"; + data[i] = ReadDouble(section_name, edited_key_name.str().c_str()); } } @@ -88,16 +88,16 @@ void IniAccess::ReadQuaternion(const char* section_name, const char* key_name, l double norm = 0.0; for (int i = 0; i < 4; i++) { // Read Quaternion as new format - std::stringstream c_name; - c_name << key_name << "_(" << i << ")"; - temp[i] = ReadDouble(section_name, c_name.str().c_str()); + std::stringstream edited_key_name; + edited_key_name << key_name << "_(" << i << ")"; + temp[i] = ReadDouble(section_name, edited_key_name.str().c_str()); norm += temp[i] * temp[i]; } if (norm == 0.0) { // If it is not new format, try to read old format for (int i = 0; i < 4; i++) { - std::stringstream c_name; - c_name << key_name << "(" << i << ")"; - data[i] = ReadDouble(section_name, c_name.str().c_str()); + std::stringstream edited_key_name; + edited_key_name << key_name << "(" << i << ")"; + data[i] = ReadDouble(section_name, edited_key_name.str().c_str()); } } else { data[0] = temp[0]; @@ -111,15 +111,15 @@ void IniAccess::ReadChar(const char* section_name, const char* key_name, const i #ifdef WIN32 GetPrivateProfileStringA(section_name, key_name, 0, data, size, file_path_char_); #else - std::string sdata = ReadString(section_name, key_name); - strncpy(data, sdata.c_str(), size); + std::string string_data = ReadString(section_name, key_name); + strncpy(data, string_data.c_str(), size); #endif } std::string IniAccess::ReadString(const char* section_name, const char* key_name) { #ifdef WIN32 - char temp[1024]; - ReadChar(section_name, key_name, 1024, temp); + char temp[kMaxCharLength]; + ReadChar(section_name, key_name, kMaxCharLength, temp); return string(temp); #else std::string value = ini_reader_.GetString(section_name, key_name, "NULL"); @@ -128,21 +128,20 @@ std::string IniAccess::ReadString(const char* section_name, const char* key_name } bool IniAccess::ReadEnable(const char* section_name, const char* key_name) { - std::string enablestr = ReadString(section_name, key_name); - if (enablestr.compare("ENABLE") == 0) return true; - if (enablestr.compare("1") == 0) return true; + std::string enable_string = ReadString(section_name, key_name); + if (enable_string.compare("ENABLE") == 0) return true; + if (enable_string.compare("1") == 0) return true; return false; } std::vector IniAccess::ReadStrVector(const char* section_name, const char* key_name) { - const static unsigned int buf_size = 1024; std::vector data; - char temp[buf_size]; + char temp[kMaxCharLength]; unsigned int i = 0; while (true) { std::stringstream c_name; c_name << key_name << "(" << i << ")"; - ReadChar(section_name, c_name.str().c_str(), buf_size, temp); + ReadChar(section_name, c_name.str().c_str(), kMaxCharLength, temp); #ifdef WIN32 if (temp[0] == NULL) { #else @@ -176,13 +175,13 @@ void IniAccess::ReadCsvDouble(std::vector>& output_value, co int line_num = 0; output_value.reserve(node_num); while (getline(ifs, line)) { - std::vector strvec = Split(line, ','); - std::vector tempdoublevec; - tempdoublevec.reserve(node_num); - for (size_t i = 0; i < strvec.size(); i++) { - tempdoublevec.push_back(std::stod(strvec.at(i))); + std::vector string_vector = Split(line, ','); + std::vector temp; + temp.reserve(node_num); + for (size_t i = 0; i < string_vector.size(); i++) { + temp.push_back(std::stod(string_vector.at(i))); } - output_value.push_back(tempdoublevec); + output_value.push_back(temp); line_num++; } } @@ -196,9 +195,9 @@ void IniAccess::ReadCsvString(std::vector>& output_valu int line_num = 0; output_value.reserve(node_num); while (getline(ifs, line)) { - std::vector tempstrvec = Split(line, ','); - tempstrvec.reserve(node_num); - output_value.push_back(tempstrvec); + std::vector temp = Split(line, ','); + temp.reserve(node_num); + output_value.push_back(temp); line_num++; } } diff --git a/src/library/initialize/initialize_file_access.hpp b/src/library/initialize/initialize_file_access.hpp index ecde4664b..d06eefac9 100644 --- a/src/library/initialize/initialize_file_access.hpp +++ b/src/library/initialize/initialize_file_access.hpp @@ -15,6 +15,7 @@ #else #include #endif + #include #include #include From 363fead005e509295d0dab6ba1c2b12ed12fa6f8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:26:31 +0100 Subject: [PATCH 0627/1086] Fix small --- src/environment/global/gnss_satellites.cpp | 18 ++++++++++-------- src/environment/global/hipparcos_catalogue.cpp | 4 ++-- src/environment/global/hipparcos_catalogue.hpp | 4 ++-- 3 files changed, 14 insertions(+), 12 deletions(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index d8ac30a60..28878c861 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -82,10 +82,11 @@ double get_unixtime_from_timestamp_line(std::vector& s) { } template -Vector GnssSat_coordinate::TrigonometricInterpolation(const vector& time_vector, const vector>& values, double time) const { +libra::Vector GnssSat_coordinate::TrigonometricInterpolation(const vector& time_vector, const vector>& values, + double time) const { int n = time_vector.size(); double w = libra::tau / (24.0 * 60.0 * 60.0) * 1.03; // coefficient of a day long - Vector res(0.0); + libra::Vector res(0.0); for (int i = 0; i < n; ++i) { double t_k = 1.0; @@ -119,9 +120,10 @@ double GnssSat_coordinate::TrigonometricInterpolation(const vector& time } template -Vector GnssSat_coordinate::LagrangeInterpolation(const vector& time_vector, const vector>& values, double time) const { +libra::Vector GnssSat_coordinate::LagrangeInterpolation(const vector& time_vector, const vector>& values, + double time) const { int n = time_vector.size(); - Vector res(0.0); + libra::Vector res(0.0); for (int i = 0; i < n; ++i) { double l_i = 1.0; @@ -357,8 +359,8 @@ pair GnssSat_position::Init(vector>& file, int in void GnssSat_position::SetUp(const double start_unix_time, const double step_sec) { step_sec_ = step_sec; - gnss_sat_ecef_.assign(all_sat_num_, Vector<3>(0.0)); - gnss_sat_eci_.assign(all_sat_num_, Vector<3>(0.0)); + gnss_sat_ecef_.assign(all_sat_num_, libra::Vector<3>(0.0)); + gnss_sat_eci_.assign(all_sat_num_, libra::Vector<3>(0.0)); validate_.assign(all_sat_num_, false); nearest_index_.resize(all_sat_num_); @@ -491,12 +493,12 @@ void GnssSat_position::Update(const double now_unix_time) { } libra::Vector<3> GnssSat_position::GetSatEcef(int sat_id) const { - if (sat_id >= all_sat_num_) return Vector<3>(0.0); + if (sat_id >= all_sat_num_) return libra::Vector<3>(0.0); return gnss_sat_ecef_.at(sat_id); } libra::Vector<3> GnssSat_position::GetSatEci(int sat_id) const { - if (sat_id >= all_sat_num_) return Vector<3>(0.0); + if (sat_id >= all_sat_num_) return libra::Vector<3>(0.0); return gnss_sat_eci_.at(sat_id); } diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index 4e0f0323f..9bba26564 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -61,12 +61,12 @@ libra::Vector<3> HipparcosCatalogue::GetStarDirection_i(int rank) const { return direction_i; } -libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, Quaternion quaternoin_i2b) const { +libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, libra::Quaternion quaternion_i2b) const { libra::Vector<3> direction_i; libra::Vector<3> direction_b; direction_i = GetStarDirection_i(rank); - direction_b = quaternoin_i2b.frame_conv(direction_i); + direction_b = quaternion_i2b.frame_conv(direction_i); return direction_b; } diff --git a/src/environment/global/hipparcos_catalogue.hpp b/src/environment/global/hipparcos_catalogue.hpp index 236f9a33f..8adce4b69 100644 --- a/src/environment/global/hipparcos_catalogue.hpp +++ b/src/environment/global/hipparcos_catalogue.hpp @@ -87,9 +87,9 @@ class HipparcosCatalogue : public ILoggable { *@fn GetStarDir_b *@brief Return direction vector of a star in the body-fixed frame *@param [in] rank: Rank of star magnitude in read catalogue - *@param [in] quaternoin_i2b: Quaternion from the inertial frame to the body-fixed frame + *@param [in] quaternion_i2b: Quaternion from the inertial frame to the body-fixed frame */ - libra::Vector<3> GetStarDirection_b(int rank, Quaternion quaternoin_i2b) const; + libra::Vector<3> GetStarDirection_b(int rank, libra::Quaternion quaternion_i2b) const; // Override ILoggable /** From ed69d9717c3da47da15c7ce4766a629c095a1569 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:33:04 +0100 Subject: [PATCH 0628/1086] Add libra:: --- src/environment/local/geomagnetic_field.cpp | 4 ++-- src/environment/local/local_celestial_information.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 5aec7f26c..6e5bc2eb6 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -40,8 +40,8 @@ void GeomagneticField::CalcMagneticField(const double decimal_year, const double } void GeomagneticField::AddNoise(double* magnetic_field_array_i_nT) { - static Vector<3> standard_deviation(random_walk_standard_deviation_nT_); - static Vector<3> limit(random_walk_limit_nT_); + static libra::Vector<3> standard_deviation(random_walk_standard_deviation_nT_); + static libra::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_, g_rand.MakeSeed()); diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 0565b0d10..2449d66ff 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -140,7 +140,7 @@ libra::Vector<3> LocalCelestialInformation::GetPositionFromSpacecraft_i_m(const return position; } -Vector<3> LocalCelestialInformation::GetCenterBodyPositionFromSpacecraft_i_m() const { +libra::Vector<3> LocalCelestialInformation::GetCenterBodyPositionFromSpacecraft_i_m() const { std::string body_name = global_celestial_information_->GetCenterBodyName(); libra::Vector<3> position = GetPositionFromSpacecraft_i_m(body_name.c_str()); return position; From f19e74f8be7a20af2c4422f347adfffda13ad49b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:34:40 +0100 Subject: [PATCH 0629/1086] Add libra:: --- src/dynamics/orbit/initialize_orbit.cpp | 34 ++++++++++++------------- src/dynamics/orbit/initialize_orbit.hpp | 2 +- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index d6540fd24..d6e188662 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -26,9 +26,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string if (propagate_mode == "RK4") { // initialize RK4 orbit propagator - Vector<3> position_i_m; - Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + libra::Vector<3> position_i_m; + libra::Vector<3> velocity_i_m_s; + libra::Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; @@ -49,9 +49,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string RelativeOrbitModel relative_dynamics_model_type = (RelativeOrbitModel)(conf.ReadInt(section_, "relative_dynamics_model_type")); STMModel stm_model_type = (STMModel)(conf.ReadInt(section_, "stm_model_type")); - Vector<3> init_relative_position_lvlh; + libra::Vector<3> init_relative_position_lvlh; conf.ReadVector<3>(section_, "initial_relative_position_lvlh_m", init_relative_position_lvlh); - Vector<3> init_relative_velocity_lvlh; + libra::Vector<3> init_relative_velocity_lvlh; conf.ReadVector<3>(section_, "initial_relative_velocity_lvlh_m_s", init_relative_velocity_lvlh); // There is a possibility that the orbit of the reference sat is not initialized when RelativeOrbit initialization is called To ensure that @@ -67,9 +67,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // TODO: init_mode_kepler should be removed in the next major update if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { // initialize with position and velocity - Vector<3> init_pos_m; + libra::Vector<3> init_pos_m; conf.ReadVector<3>(section_, "initial_position_i_m", init_pos_m); - Vector<3> init_vel_m_s; + libra::Vector<3> init_vel_m_s; conf.ReadVector<3>(section_, "initial_velocity_i_m_s", init_vel_m_s); oe = OrbitalElements(mu_m3_s2, current_time_jd, init_pos_m, init_vel_m_s); } else { @@ -86,9 +86,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string orbit = new KeplerOrbitPropagation(celestial_information, current_time_jd, kepler_orbit); } else if (propagate_mode == "ENCKE") { // initialize orbit for Encke's method - Vector<3> position_i_m; - Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + libra::Vector<3> position_i_m; + libra::Vector<3> velocity_i_m_s; + libra::Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; @@ -100,9 +100,9 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; - Vector<3> position_i_m; - Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + libra::Vector<3> position_i_m; + libra::Vector<3> velocity_i_m_s; + libra::Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; @@ -115,12 +115,12 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string return orbit; } -Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section) { +libra::Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section) { auto conf = IniAccess(initialize_file); const char* section_ = section.c_str(); - Vector<3> position_i_m; - Vector<3> velocity_i_m_s; - Vector<6> pos_vel; + libra::Vector<3> position_i_m; + libra::Vector<3> velocity_i_m_s; + libra::Vector<6> pos_vel; OrbitInitializeMode initialize_mode = SetOrbitInitializeMode(conf.ReadString(section_, "initialize_mode")); if (initialize_mode == OrbitInitializeMode::kOrbitalElements) { diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index e41755506..72bc8b82a 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -34,6 +34,6 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string * @param [in] mu_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name */ -Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); +libra::Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); #endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ From a3202e7a9714048cbe4f1bc767eb0c8e13c8c60b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:35:47 +0100 Subject: [PATCH 0630/1086] Remove using --- src/library/logger/log_utility.hpp | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/src/library/logger/log_utility.hpp b/src/library/logger/log_utility.hpp index c6be4e191..9a8113fa4 100644 --- a/src/library/logger/log_utility.hpp +++ b/src/library/logger/log_utility.hpp @@ -11,9 +11,6 @@ #include #include #include -using libra::Matrix; -using libra::Quaternion; -using libra::Vector; /** * @fn WriteScalar @@ -38,7 +35,7 @@ inline std::string WriteScalar(std::string name, std::string unit); * @param [in] precision: precision for the value (number of digit) */ template -inline std::string WriteVector(Vector vec, int precision = 6); +inline std::string WriteVector(libra::Vector vec, int precision = 6); /** * @fn WriteVector * @brief Write header for vector value @@ -56,7 +53,7 @@ inline std::string WriteVector(std::string name, std::string frame, std::string * @note TODO: add precision? */ template -inline std::string WriteMatrix(Matrix mat); +inline std::string WriteMatrix(libra::Matrix mat); /** * @fn WriteMatrix * @brief Write header for matrix value @@ -74,7 +71,7 @@ inline std::string WriteMatrix(std::string name, std::string frame, std::string * @param [in] quat: Quaternion * @note TODO: add function for headers? */ -inline std::string WriteQuaternion(Quaternion quat); +inline std::string WriteQuaternion(libra::Quaternion quat); /** * @fn WriteQuaternion * @brief Write header for quaternion @@ -95,7 +92,7 @@ std::string WriteScalar(T scalar, int precision) { std::string WriteScalar(std::string name, std::string unit) { return name + "[" + unit + "],"; } template -std::string WriteVector(Vector vec, int precision) { +std::string WriteVector(libra::Vector vec, int precision) { std::stringstream str_tmp; for (size_t n = 0; n < NUM; n++) { @@ -119,7 +116,7 @@ std::string WriteVector(std::string name, std::string frame, std::string unit, s } template -std::string WriteMatrix(Matrix mat) { +std::string WriteMatrix(libra::Matrix mat) { std::stringstream str_tmp; for (size_t n = 0; n < ROW; n++) { @@ -141,7 +138,7 @@ std::string WriteMatrix(std::string name, std::string frame, std::string unit, s return str_tmp.str(); } -std::string WriteQuaternion(Quaternion quat) { +std::string WriteQuaternion(libra::Quaternion quat) { std::stringstream str_tmp; for (size_t i = 0; i < 4; i++) { From 12ae724c4fc7119f8335afb6c1a2b97237564ee5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:36:48 +0100 Subject: [PATCH 0631/1086] Add libra:: --- src/environment/local/geomagnetic_field.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index 6e5bc2eb6..3552866b4 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -23,7 +23,7 @@ GeomagneticField::GeomagneticField(const std::string igrf_file_name, const doubl } void GeomagneticField::CalcMagneticField(const double decimal_year, const double sidereal_day, const GeodeticPosition position, - const Quaternion quaternion_i2b) { + const libra::Quaternion quaternion_i2b) { if (!IsCalcEnabled) return; const double lat_rad = position.GetLat_rad(); From 8a45282167be7bdc4f73e7c52b5227935b45ecfb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:43:24 +0100 Subject: [PATCH 0632/1086] Add libra:: --- src/dynamics/orbit/initialize_orbit.cpp | 1 - src/dynamics/orbit/orbit.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/thermal/initialize_node.cpp | 2 +- src/dynamics/thermal/node.cpp | 4 ++-- src/dynamics/thermal/node.hpp | 10 +++++----- src/dynamics/thermal/temperature.cpp | 6 +++--- src/dynamics/thermal/temperature.hpp | 6 +++--- 8 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index d6e188662..e8940b2d1 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -62,7 +62,6 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, relative_information); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation - double mu_m3_s2 = mu_m3_s2; OrbitalElements oe; // TODO: init_mode_kepler should be removed in the next major update if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 58e2bb9e9..24e2335ed 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -4,7 +4,7 @@ */ #include "orbit.hpp" -Quaternion Orbit::CalcQuaternion_i2lvlh() const { +libra::Quaternion Orbit::CalcQuaternion_i2lvlh() const { libra::Vector<3> lvlh_x = spacecraft_position_i_m_; // x-axis in LVLH frame is position vector direction from geocenter to satellite libra::Vector<3> lvlh_ex = normalize(lvlh_x); libra::Vector<3> lvlh_z = diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index befe3f427..0a54ddc6f 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -38,7 +38,7 @@ void Rk4OrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Ve (void)t; } -void Rk4OrbitPropagation::Initialize(Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) { +void Rk4OrbitPropagation::Initialize(libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) { // state vector [x,y,z,vx,vy,vz] libra::Vector<6> init_state; init_state[0] = position_i_m[0]; diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index cbf26ecb2..85530b9ab 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -51,7 +51,7 @@ Node InitNode(const std::vector& node_str) { capacity = stod(node_str[3]); // column 4 alpha = stod(node_str[4]); // column 5 area = stod(node_str[5]); // column 6 - Vector<3> normal_v_b; // column 7-9 + libra::Vector<3> normal_v_b; // column 7-9 for (int i = 0; i < 3; i++) { normal_v_b[i] = stod(node_str[6 + i]); } // body frame diff --git a/src/dynamics/thermal/node.cpp b/src/dynamics/thermal/node.cpp index f4e88a40b..a82775434 100644 --- a/src/dynamics/thermal/node.cpp +++ b/src/dynamics/thermal/node.cpp @@ -12,7 +12,7 @@ using namespace std; using namespace libra; Node::Node(const int node_id, const string node_label, const int heater_node_id, const double temperature_ini, const double capacity_ini, - const double internal_heat_ini, const double alpha, const double area, Vector<3> normal_v_b) + const double internal_heat_ini, const double alpha, const double area, libra::Vector<3> normal_v_b) : node_id_(node_id), node_label_(node_label), heater_node_id_(heater_node_id), @@ -57,7 +57,7 @@ void Node::SetInternalHeat(double heat_power) { internal_heat_ = heat_power; // [W] } -double Node::CalcSolarRadiation(Vector<3> sun_direction) { +double Node::CalcSolarRadiation(libra::Vector<3> sun_direction) { // FIXME: constants double R = 6.96E+8; // Distance from sun double T = 5778; // sun surface temperature [K] diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index 1a429fb2a..e0932036e 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -19,19 +19,19 @@ class Node { double capacity_; // 熱容量[J/K] double internal_heat_; // 内部生成熱[J] double alpha_; - double area_; // 太陽熱が入射する面の面積[m^2] - Vector<3> normal_v_b_; // 太陽熱が入射する面の法線ベクトル(機体固定座標系) - double solar_radiation_; // 入射する太陽輻射熱[W]([J]に変換するためには時間をかけないといけないことに注意 + double area_; // 太陽熱が入射する面の面積[m^2] + libra::Vector<3> normal_v_b_; // 太陽熱が入射する面の法線ベクトル(機体固定座標系) + double solar_radiation_; // 入射する太陽輻射熱[W]([J]に変換するためには時間をかけないといけないことに注意 double K2deg(double kelvin) const; // 絶対温度からdegCに変換 public: Node(const int node_id, const std::string node_label, const int heater_node_id, const double temperature_ini, const double capacity_ini, - const double internal_heat_ini, const double alpha, const double area, Vector<3> normal_v_b); + const double internal_heat_ini, const double alpha, const double area, libra::Vector<3> normal_v_b); virtual ~Node(); // 熱計算用関数 - double CalcSolarRadiation(Vector<3> sun_direction); // 太陽入射熱を計算 + double CalcSolarRadiation(libra::Vector<3> sun_direction); // 太陽入射熱を計算 // Output from this class int GetNodeId(void) const; diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index 7108a0429..8eee383d7 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -36,7 +36,7 @@ Temperature::Temperature() { Temperature::~Temperature() {} -void Temperature::Propagate(Vector<3> sun_direction, const double endtime) { +void Temperature::Propagate(libra::Vector<3> sun_direction, const double endtime) { if (!is_calc_enabled_) return; while (endtime - prop_time_ - prop_step_ > 1.0e-6) { RungeOneStep(prop_time_, prop_step_, sun_direction, node_num_); @@ -64,7 +64,7 @@ void Temperature::Propagate(Vector<3> sun_direction, const double endtime) { } } -void Temperature::RungeOneStep(double t, double dt, Vector<3> sun_direction, int node_num) { +void Temperature::RungeOneStep(double t, double dt, libra::Vector<3> sun_direction, int node_num) { vector x(node_num); for (int i = 0; i < node_num; i++) { x[i] = vnodes_[i].GetTemperature_K(); @@ -100,7 +100,7 @@ void Temperature::RungeOneStep(double t, double dt, Vector<3> sun_direction, int } } -vector Temperature::OdeTemperature(vector x, double t, Vector<3> sun_direction, int node_num) { +vector Temperature::OdeTemperature(vector x, double t, libra::Vector<3> sun_direction, int node_num) { // TODO: consider the following unused arguments are really needed UNUSED(x); UNUSED(t); diff --git a/src/dynamics/thermal/temperature.hpp b/src/dynamics/thermal/temperature.hpp index 7bed885f8..63f4a3c79 100644 --- a/src/dynamics/thermal/temperature.hpp +++ b/src/dynamics/thermal/temperature.hpp @@ -23,8 +23,8 @@ class Temperature : public ILoggable { bool is_calc_enabled_; // 温度更新をするかどうかのブーリアン bool debug_; - void RungeOneStep(double t, double dt, Vector<3> sun_direction, int node_num); - std::vector OdeTemperature(std::vector x, double t, const Vector<3> sun_direction, + void RungeOneStep(double t, double dt, libra::Vector<3> sun_direction, int node_num); + std::vector OdeTemperature(std::vector x, double t, const libra::Vector<3> sun_direction, int node_num); // 温度に関する常微分方程式, xはnodeの温度をならべたもの public: @@ -32,7 +32,7 @@ class Temperature : public ILoggable { const double propstep, const bool is_calc_enabled, const bool debug); Temperature(); virtual ~Temperature(); - void Propagate(Vector<3> sun_direction, + void Propagate(libra::Vector<3> sun_direction, const double endtime); // 太陽入熱量計算のため, 太陽方向の情報を入手 std::vector GetVnodes() const; void AddHeaterPower(std::vector heater_power); From e8835faef5533a5a1f9577d6ec6a7df92329609e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:45:15 +0100 Subject: [PATCH 0633/1086] Add libra:: --- src/dynamics/orbit/orbit.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 24e2335ed..7470ce3c1 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -24,7 +24,7 @@ libra::Quaternion Orbit::CalcQuaternion_i2lvlh() const { dcm_i2lvlh[2][1] = lvlh_ez[1]; dcm_i2lvlh[2][2] = lvlh_ez[2]; - libra::Quaternion q_i2lvlh = Quaternion::fromDCM(dcm_i2lvlh); + libra::Quaternion q_i2lvlh = libra::Quaternion::fromDCM(dcm_i2lvlh); return q_i2lvlh.normalize(); } From 314407478dad7533189dbc2eb38d4941919b8085 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:49:24 +0100 Subject: [PATCH 0634/1086] Add libra:: --- src/dynamics/attitude/attitude_rk4.hpp | 9 +++++---- src/dynamics/attitude/controlled_attitude.hpp | 14 +++++++------- src/dynamics/attitude/initialize_attitude.cpp | 12 ++++++------ src/dynamics/attitude/initialize_attitude.hpp | 2 +- 4 files changed, 19 insertions(+), 18 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index b7324e9ef..dc7bc2d54 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -24,8 +24,9 @@ class AttitudeRk4 : public Attitude { * @param [in] propagation_step_s: Initial value of propagation step width [sec] * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - AttitudeRk4(const Vector<3>& angular_velocity_b_rad_s, const Quaternion& quaternion_i2b, const Matrix<3, 3>& inertia_tensor_kgm2, - const Vector<3>& torque_b_Nm, const double propagation_step_s, const std::string& simulation_object_name = "Attitude"); + AttitudeRk4(const libra::Vector<3>& angular_velocity_b_rad_s, const libra::Quaternion& quaternion_i2b, + const libra::Matrix<3, 3>& inertia_tensor_kgm2, const libra::Vector<3>& torque_b_Nm, const double propagation_step_s, + const std::string& simulation_object_name = "Attitude"); /** * @fn ~AttitudeRk4 * @brief Destructor @@ -54,14 +55,14 @@ class AttitudeRk4 : public Attitude { * @brief Generate angular velocity matrix for kinematics calculation * @param [in] angular_velocity_b_rad_s: Angular velocity [rad/s] */ - Matrix<4, 4> CalcAngularVelocityMatrix(Vector<3> angular_velocity_b_rad_s); + libra::Matrix<4, 4> CalcAngularVelocityMatrix(libra::Vector<3> angular_velocity_b_rad_s); /** * @fn AttitudeDynamicsAndKinematics * @brief Dynamics equation with kinematics * @param [in] x: State vector (angular velocity and quaternion) * @param [in] t: Unused TODO: remove? */ - Vector<7> AttitudeDynamicsAndKinematics(Vector<7> x, double t); + libra::Vector<7> AttitudeDynamicsAndKinematics(libra::Vector<7> x, double t); /** * @fn RungeKuttaOneStep * @brief Equation for one step of Runge-Kutta method diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 934bbad12..9627c8a0d 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -53,8 +53,8 @@ class ControlledAttitude : public Attitude { * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const Quaternion quaternion_i2b, - const Vector<3> main_target_direction_b, const Vector<3> sub_target_direction_b, const Matrix<3, 3>& inertia_tensor_kgm2, - const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, + const libra::Vector<3> main_target_direction_b, const libra::Vector<3> sub_target_direction_b, + const libra::Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, const std::string& simulation_object_name = "Attitude"); /** * @fn ~ControlledAttitude @@ -82,12 +82,12 @@ class ControlledAttitude : public Attitude { * @fn SetMainTargetDirection_b * @brief Set main target direction on the body fixed frame */ - inline void SetMainTargetDirection_b(Vector<3> main_target_direction_b) { main_target_direction_b_ = main_target_direction_b; } + inline void SetMainTargetDirection_b(libra::Vector<3> main_target_direction_b) { main_target_direction_b_ = main_target_direction_b; } /** * @fn SetSubTargetDirection_b * @brief Set sub target direction on the body fixed frame */ - inline void SetSubTargetDirection_b(Vector<3> sub_target_direction_b) { sub_target_direction_b_ = sub_target_direction_b; } + inline void SetSubTargetDirection_b(libra::Vector<3> sub_target_direction_b) { sub_target_direction_b_ = sub_target_direction_b; } /** * @fn Propagate @@ -121,14 +121,14 @@ class ControlledAttitude : public Attitude { * @param [in] mode: Attitude control mode * @return Target direction at the inertia frame0 */ - Vector<3> CalcTargetDirection_i(AttitudeControlMode mode); + libra::Vector<3> CalcTargetDirection_i(AttitudeControlMode mode); /** * @fn PointingControl * @brief Calculate attitude quaternion * @param [in] main_direction_i: Main target direction in the inertial frame * @param [in] sub_direction_i: Sub target direction in the inertial frame */ - void PointingControl(const Vector<3> main_direction_i, const Vector<3> sub_direction_i); + void PointingControl(const libra::Vector<3> main_direction_i, const libra::Vector<3> sub_direction_i); /** * @fn CalcAngularVelocity * @brief Calculate angular velocity @@ -141,7 +141,7 @@ class ControlledAttitude : public Attitude { * @param [in] main_direction: Main target direction * @param [in] sub_direction: Sub target direction */ - Matrix<3, 3> CalcDcm(const Vector<3> main_direction, const Vector<3> sub_direction); + libra::Matrix<3, 3> CalcDcm(const libra::Vector<3> main_direction, const libra::Vector<3> sub_direction); }; #endif // S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 1ecd982d6..97bbeca92 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -7,7 +7,7 @@ #include Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* local_celestial_information, - const double step_width_s, const Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id) { + const double step_width_s, const libra::Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id) { IniAccess ini_file(file_name); const char* section_ = "ATTITUDE"; std::string mc_name = section_ + std::to_string(spacecraft_id); // FIXME @@ -17,11 +17,11 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel if (propagate_mode == "RK4") { // RK4 propagator - Vector<3> omega_b; + libra::Vector<3> omega_b; ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); Quaternion quaternion_i2b; ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); - Vector<3> torque_b; + libra::Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); @@ -36,7 +36,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel AttitudeControlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); Quaternion quaternion_i2b; ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); - Vector<3> main_target_direction_b, sub_target_direction_b; + libra::Vector<3> main_target_direction_b, sub_target_direction_b; ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor_kgm2, @@ -45,11 +45,11 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel std::cerr << "ERROR: attitude propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The attitude mode is automatically set as RK4" << std::endl; - Vector<3> omega_b; + libra::Vector<3> omega_b; ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); Quaternion quaternion_i2b; ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); - Vector<3> torque_b; + libra::Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); diff --git a/src/dynamics/attitude/initialize_attitude.hpp b/src/dynamics/attitude/initialize_attitude.hpp index 123e55a98..6b74bfd2a 100644 --- a/src/dynamics/attitude/initialize_attitude.hpp +++ b/src/dynamics/attitude/initialize_attitude.hpp @@ -21,6 +21,6 @@ * @param [in] spacecraft_id: Satellite ID */ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCelestialInformation* local_celestial_information, - const double step_width_s, const Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id); + const double step_width_s, const libra::Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id); #endif // S2E_DYNAMICS_ATTITUDE_INITIALIZE_ATTITUDE_HPP_ From 7a0c7727b93792fdfd1911be86afc50fe65cf297 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 14:54:42 +0100 Subject: [PATCH 0635/1086] Add libra:: --- .../real/aocs/initialize_reaction_wheel.cpp | 6 ++--- .../real/aocs/initialize_sun_sensor.cpp | 4 +-- src/components/real/aocs/reaction_wheel.cpp | 25 ++++++++++--------- src/components/real/aocs/reaction_wheel.hpp | 10 ++++---- src/components/real/aocs/sun_sensor.cpp | 10 ++++---- src/components/real/aocs/sun_sensor.hpp | 4 +-- .../power/initialize_solar_array_panel.cpp | 4 +-- 7 files changed, 32 insertions(+), 31 deletions(-) diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index 31b14ecc5..a15c38819 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -59,11 +59,11 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double rwmodel_conf.ReadQuaternion(RWsection, "quaternion_b2c", q_b2c); } else // direction_determination_mode == "DIRECTION" { - Vector<3> direction_b; + libra::Vector<3> direction_b; rwmodel_conf.ReadVector(RWsection, "direction_b", direction_b); - Vector<3> direction_c(0.0); + libra::Vector<3> direction_c(0.0); direction_c[2] = 1.0; - Quaternion q(direction_b, direction_c); + libra::Quaternion q(direction_b, direction_c); q_b2c = q.conjugate(); } diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index ae809c1c5..ca09b7a9d 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -20,7 +20,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n int prescaler = ss_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion q_b2c; + libra::Quaternion q_b2c; ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; @@ -53,7 +53,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss int prescaler = ss_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion q_b2c; + libra::Quaternion q_b2c; ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 7222b5eae..53e04c801 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -18,11 +18,11 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, const int id, double step_width, double dt_main_routine, - double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, Vector<3> pos_b, - double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, - double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, - double init_velocity) + double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion q_b2c, + libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, + bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, + vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, + bool considers_structural_resonance, bool drive_flag, double init_velocity) : ComponentBase(prescaler, clock_gen, fast_prescaler), id_(id), inertia_(inertia), @@ -45,9 +45,10 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, c } RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, double step_width, - double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, Quaternion q_b2c, - Vector<3> pos_b, double dead_time, Vector<3> driving_lag_coef, Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, - bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, + double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, + libra::Quaternion q_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, + libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, + vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : ComponentBase(prescaler, clock_gen, power_port, fast_prescaler), @@ -72,13 +73,13 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, P } void RWModel::Initialize() { - direction_c_ = Vector<3>(0.0); + direction_c_ = libra::Vector<3>(0.0); direction_c_[2] = 1.0; direction_b_ = q_b2c_.frame_conv_inv(direction_c_); velocity_limit_rpm_ = max_velocity_rpm_; - output_torque_b_ = Vector<3>(0.0); - angular_momentum_b_ = Vector<3>(0.0); + output_torque_b_ = libra::Vector<3>(0.0); + angular_momentum_b_ = libra::Vector<3>(0.0); target_accl_ = 0.0; int len_buffer = (int)floor(dead_time_ / dt_main_routine_) + 1; delay_buffer_accl_.assign(len_buffer, 0.0); @@ -104,7 +105,7 @@ void RWModel::PowerOffRoutine() { drive_flag_ = 0; } // Jitter calculation void RWModel::FastUpdate() { rw_jitter_.CalcJitter(angular_velocity_rad_); } -Vector<3> RWModel::CalcTorque() { +libra::Vector<3> RWModel::CalcTorque() { double pre_angular_velocity_rad = angular_velocity_rad_; if (!drive_flag_) // RW power off -> coasting mode { diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 96ff42604..b15231576 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -56,8 +56,8 @@ class RWModel : public ComponentBase, public ILoggable { */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const Quaternion q_b2c, const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, - const Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, + const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, + const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); @@ -93,8 +93,8 @@ class RWModel : public ComponentBase, public ILoggable { */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const Quaternion q_b2c, const Vector<3> pos_b, const double dead_time, const Vector<3> driving_lag_coef, - const Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, + const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, + const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); @@ -227,7 +227,7 @@ class RWModel : public ComponentBase, public ILoggable { * @fn CalcTorque * @brief Calculation of generated torque */ - Vector<3> CalcTorque(); + libra::Vector<3> CalcTorque(); /** * @fn Initialize * @brief Initialize function diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 6dfb525f3..45f340b45 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -57,8 +57,8 @@ void SunSensor::MainRoutine(int count) { } void SunSensor::measure() { - Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); - Vector<3> sun_dir_b = normalize(sun_pos_b); + libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); + libra::Vector<3> sun_dir_b = normalize(sun_pos_b); sun_c_ = q_b2c_.frame_conv(sun_dir_b); // Frame conversion from body to component @@ -85,7 +85,7 @@ void SunSensor::measure() { measured_sun_c_ = normalize(measured_sun_c_); } else { - measured_sun_c_ = Vector<3>(0); + measured_sun_c_ = libra::Vector<3>(0); alpha_ = 0.0; beta_ = 0.0; } @@ -94,7 +94,7 @@ void SunSensor::measure() { } void SunSensor::SunDetectionJudgement() { - Vector<3> sun_direction_c = normalize(sun_c_); + libra::Vector<3> sun_direction_c = normalize(sun_c_); double sun_angle_ = acos(sun_direction_c[2]); @@ -110,7 +110,7 @@ void SunSensor::SunDetectionJudgement() { } void SunSensor::CalcSolarIlluminance() { - Vector<3> sun_direction_c = normalize(sun_c_); + libra::Vector<3> sun_direction_c = normalize(sun_c_); double sun_angle_ = acos(sun_direction_c[2]); if (sun_angle_ > libra::pi_2) { diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index bf94398a6..aef5a6b63 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -79,8 +79,8 @@ class SunSensor : public ComponentBase, public ILoggable { // Getter inline bool GetSunDetectedFlag() const { return sun_detected_flag_; }; - inline const Vector<3> GetMeasuredSun_c() const { return measured_sun_c_; }; - inline const Vector<3> GetMeasuredSun_b() const { return q_b2c_.conjugate().frame_conv(measured_sun_c_); }; + inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_c_; }; + inline const libra::Vector<3> GetMeasuredSun_b() const { return q_b2c_.conjugate().frame_conv(measured_sun_c_); }; inline double GetSunAngleAlpha() const { return alpha_; }; inline double GetSunAngleBeta() const { return beta_; }; inline double GetSolarIlluminance() const { return solar_illuminance_; }; diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index 692d8f031..250289456 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -31,7 +31,7 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons double cell_area; cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); - Vector<3> normal_vector; + libra::Vector<3> normal_vector; sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); double cell_efficiency; @@ -67,7 +67,7 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons double cell_area; cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); - Vector<3> normal_vector; + libra::Vector<3> normal_vector; sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); double cell_efficiency; From 4a6ac979149ddbb49dc9141ae80701fa8da0c405 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:07:52 +0100 Subject: [PATCH 0636/1086] Fix function argument name --- src/library/logger/log_utility.hpp | 26 ++++++++++++-------------- 1 file changed, 12 insertions(+), 14 deletions(-) diff --git a/src/library/logger/log_utility.hpp b/src/library/logger/log_utility.hpp index 9a8113fa4..a1d8aeb53 100644 --- a/src/library/logger/log_utility.hpp +++ b/src/library/logger/log_utility.hpp @@ -31,11 +31,11 @@ inline std::string WriteScalar(std::string name, std::string unit); /** * @fn WriteVector * @brief Write Vector value - * @param [in] vec: vector value + * @param [in] vector: vector value * @param [in] precision: precision for the value (number of digit) */ template -inline std::string WriteVector(libra::Vector vec, int precision = 6); +inline std::string WriteVector(libra::Vector vector, int precision = 6); /** * @fn WriteVector * @brief Write header for vector value @@ -49,11 +49,10 @@ inline std::string WriteVector(std::string name, std::string frame, std::string /** * @fn WriteMatrix * @brief Write Matrix value - * @param [in] mat: matrix value - * @note TODO: add precision? + * @param [in] matrix: matrix value */ template -inline std::string WriteMatrix(libra::Matrix mat); +inline std::string WriteMatrix(libra::Matrix matrix, int precision = 6); /** * @fn WriteMatrix * @brief Write header for matrix value @@ -68,10 +67,9 @@ inline std::string WriteMatrix(std::string name, std::string frame, std::string /** * @fn WriteQuaternion * @brief Write quaternion value - * @param [in] quat: Quaternion - * @note TODO: add function for headers? + * @param [in] quaternion: Quaternion */ -inline std::string WriteQuaternion(libra::Quaternion quat); +inline std::string WriteQuaternion(libra::Quaternion quaternion, int precision = 6); /** * @fn WriteQuaternion * @brief Write header for quaternion @@ -92,11 +90,11 @@ std::string WriteScalar(T scalar, int precision) { std::string WriteScalar(std::string name, std::string unit) { return name + "[" + unit + "],"; } template -std::string WriteVector(libra::Vector vec, int precision) { +std::string WriteVector(libra::Vector vector, int precision) { std::stringstream str_tmp; for (size_t n = 0; n < NUM; n++) { - str_tmp << std::setprecision(precision) << vec[n] << ","; + str_tmp << std::setprecision(precision) << vector[n] << ","; } return str_tmp.str(); } @@ -116,12 +114,12 @@ std::string WriteVector(std::string name, std::string frame, std::string unit, s } template -std::string WriteMatrix(libra::Matrix mat) { +std::string WriteMatrix(libra::Matrix matrix, int precision) { std::stringstream str_tmp; for (size_t n = 0; n < ROW; n++) { for (size_t m = 0; m < COLUMN; m++) { - str_tmp << mat[n][m] << ","; + str_tmp << std::setprecision(precision) << matrix[n][m] << ","; } } return str_tmp.str(); @@ -138,11 +136,11 @@ std::string WriteMatrix(std::string name, std::string frame, std::string unit, s return str_tmp.str(); } -std::string WriteQuaternion(libra::Quaternion quat) { +std::string WriteQuaternion(libra::Quaternion quaternion, int precision) { std::stringstream str_tmp; for (size_t i = 0; i < 4; i++) { - str_tmp << quat[i] << ","; + str_tmp << std::setprecision(precision) << quaternion[i] << ","; } return str_tmp.str(); } From c62c5d30bfdd19735b734cdc2486541121ce5d94 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:10:21 +0100 Subject: [PATCH 0637/1086] Add const --- src/library/logger/log_utility.hpp | 32 +++++++++++++++--------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/src/library/logger/log_utility.hpp b/src/library/logger/log_utility.hpp index a1d8aeb53..798055fc4 100644 --- a/src/library/logger/log_utility.hpp +++ b/src/library/logger/log_utility.hpp @@ -19,14 +19,14 @@ * @param [in] precision: precision for the value (number of digit) */ template -inline std::string WriteScalar(T scalar, int precision = 6); +inline std::string WriteScalar(const T scalar, const int precision = 6); /** * @fn WriteScalar * @brief Write header for scalar value * @param [in] name: Name of the scalar value * @param [in] unit: Unit of the scalar value */ -inline std::string WriteScalar(std::string name, std::string unit); +inline std::string WriteScalar(const std::string name, const std::string unit); /** * @fn WriteVector @@ -35,7 +35,7 @@ inline std::string WriteScalar(std::string name, std::string unit); * @param [in] precision: precision for the value (number of digit) */ template -inline std::string WriteVector(libra::Vector vector, int precision = 6); +inline std::string WriteVector(const libra::Vector vector, const int precision = 6); /** * @fn WriteVector * @brief Write header for vector value @@ -44,7 +44,7 @@ inline std::string WriteVector(libra::Vector vector, int precision * @param [in] unit: Unit of the vector value * @param [in] n: Number of elements */ -inline std::string WriteVector(std::string name, std::string frame, std::string unit, size_t n); +inline std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t n); /** * @fn WriteMatrix @@ -52,7 +52,7 @@ inline std::string WriteVector(std::string name, std::string frame, std::string * @param [in] matrix: matrix value */ template -inline std::string WriteMatrix(libra::Matrix matrix, int precision = 6); +inline std::string WriteMatrix(const libra::Matrix matrix, const int precision = 6); /** * @fn WriteMatrix * @brief Write header for matrix value @@ -62,35 +62,35 @@ inline std::string WriteMatrix(libra::Matrix matrix, int pr * @param [in] r: Row length * @param [in] c: Column length */ -inline std::string WriteMatrix(std::string name, std::string frame, std::string unit, size_t r, size_t c); +inline std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t r, const size_t c); /** * @fn WriteQuaternion * @brief Write quaternion value * @param [in] quaternion: Quaternion */ -inline std::string WriteQuaternion(libra::Quaternion quaternion, int precision = 6); +inline std::string WriteQuaternion(const libra::Quaternion quaternion, const int precision = 6); /** * @fn WriteQuaternion * @brief Write header for quaternion * @param [in] name: Name of the value * @param [in] frame: Frame of the quaternion */ -inline std::string WriteQuaternion(std::string name, std::string frame); +inline std::string WriteQuaternion(const std::string name, const std::string frame); // // Libraries for log writing // template -std::string WriteScalar(T scalar, int precision) { +std::string WriteScalar(const T scalar, const int precision) { std::stringstream str_tmp; str_tmp << std::setprecision(precision) << scalar << ","; return str_tmp.str(); } -std::string WriteScalar(std::string name, std::string unit) { return name + "[" + unit + "],"; } +std::string WriteScalar(const std::string name, const std::string unit) { return name + "[" + unit + "],"; } template -std::string WriteVector(libra::Vector vector, int precision) { +std::string WriteVector(const libra::Vector vector, const int precision) { std::stringstream str_tmp; for (size_t n = 0; n < NUM; n++) { @@ -98,7 +98,7 @@ std::string WriteVector(libra::Vector vector, int precision) { } return str_tmp.str(); } -std::string WriteVector(std::string name, std::string frame, std::string unit, size_t n) { +std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t n) { std::stringstream str_tmp; std::string axis[3] = {"_x", "_y", "_z"}; @@ -114,7 +114,7 @@ std::string WriteVector(std::string name, std::string frame, std::string unit, s } template -std::string WriteMatrix(libra::Matrix matrix, int precision) { +std::string WriteMatrix(const libra::Matrix matrix, const int precision) { std::stringstream str_tmp; for (size_t n = 0; n < ROW; n++) { @@ -124,7 +124,7 @@ std::string WriteMatrix(libra::Matrix matrix, int precision } return str_tmp.str(); } -std::string WriteMatrix(std::string name, std::string frame, std::string unit, size_t r, size_t c) { +std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t r, const size_t c) { std::stringstream str_tmp; for (size_t i = 0; i < r; i++) { @@ -136,7 +136,7 @@ std::string WriteMatrix(std::string name, std::string frame, std::string unit, s return str_tmp.str(); } -std::string WriteQuaternion(libra::Quaternion quaternion, int precision) { +std::string WriteQuaternion(const libra::Quaternion quaternion, const int precision) { std::stringstream str_tmp; for (size_t i = 0; i < 4; i++) { @@ -144,7 +144,7 @@ std::string WriteQuaternion(libra::Quaternion quaternion, int precision) { } return str_tmp.str(); } -std::string WriteQuaternion(std::string name, std::string frame) { +std::string WriteQuaternion(const std::string name, const std::string frame) { std::stringstream str_tmp; std::string axis[4] = {"_x", "_y", "_z", "_w"}; From 3f192df698e75c933f39874f05f7b07da8b1f298 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:12:46 +0100 Subject: [PATCH 0638/1086] Fix function argument name --- src/library/logger/log_utility.hpp | 24 +++++++++++++----------- 1 file changed, 13 insertions(+), 11 deletions(-) diff --git a/src/library/logger/log_utility.hpp b/src/library/logger/log_utility.hpp index 798055fc4..6bc9fdd5c 100644 --- a/src/library/logger/log_utility.hpp +++ b/src/library/logger/log_utility.hpp @@ -42,9 +42,9 @@ inline std::string WriteVector(const libra::Vector vector, const in * @param [in] name: Name of the vector value * @param [in] frame: Frame of the vector value * @param [in] unit: Unit of the vector value - * @param [in] n: Number of elements + * @param [in] length: Number of elements */ -inline std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t n); +inline std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t length); /** * @fn WriteMatrix @@ -59,10 +59,11 @@ inline std::string WriteMatrix(const libra::Matrix matrix, * @param [in] name: Name of the matrix value * @param [in] frame: Frame of the matrix value * @param [in] unit: Unit of the matrix value - * @param [in] r: Row length - * @param [in] c: Column length + * @param [in] row_length: Row length + * @param [in] column_length: Column length */ -inline std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t r, const size_t c); +inline std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t row_length, + const size_t column_length); /** * @fn WriteQuaternion @@ -98,12 +99,12 @@ std::string WriteVector(const libra::Vector vector, const int preci } return str_tmp.str(); } -std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t n) { +std::string WriteVector(const std::string name, const std::string frame, const std::string unit, const size_t length) { std::stringstream str_tmp; std::string axis[3] = {"_x", "_y", "_z"}; - for (size_t i = 0; i < n; i++) { - if (n == 3) { + for (size_t i = 0; i < length; i++) { + if (length == 3) { str_tmp << name << "_" << frame << axis[i] << "[" << unit << "],"; } else { str_tmp << name << "_" << frame << "(" << i << ")" @@ -124,11 +125,12 @@ std::string WriteMatrix(const libra::Matrix matrix, const i } return str_tmp.str(); } -std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t r, const size_t c) { +std::string WriteMatrix(const std::string name, const std::string frame, const std::string unit, const size_t row_length, + const size_t column_length) { std::stringstream str_tmp; - for (size_t i = 0; i < r; i++) { - for (size_t j = 0; j < c; j++) { + for (size_t i = 0; i < row_length; i++) { + for (size_t j = 0; j < column_length; j++) { str_tmp << name << "_" << frame << "(" << i << j << ")" << "[" << unit << "],"; } From 35ff524b799d6a162f34c814222fb5c1625832ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:18:08 +0100 Subject: [PATCH 0639/1086] Fix public variable name --- src/disturbances/initialize_disturbances.cpp | 14 +++++++------- src/dynamics/orbit/initialize_orbit.cpp | 2 +- .../global/initialize_global_environment.cpp | 4 ++-- .../local/initialize_local_environment.cpp | 6 +++--- src/environment/local/local_environment.cpp | 2 +- src/library/logger/loggable.hpp | 2 +- src/library/logger/logger.cpp | 4 ++-- 7 files changed, 17 insertions(+), 17 deletions(-) diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 98a560bff..ca6170b27 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -22,7 +22,7 @@ AirDrag InitAirDrag(const std::string initialize_file_path, const std::vectorSetIsCalcEnabled(conf.ReadEnable(section_, "calculation")); - orbit->IsLogEnabled = conf.ReadEnable(section_, "logging"); + orbit->is_log_enabled_ = conf.ReadEnable(section_, "logging"); return orbit; } diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index e7db29cc0..542db7350 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -55,7 +55,7 @@ HipparcosCatalogue* InitHipparcosCatalogue(std::string file_name) { HipparcosCatalogue* hipparcos_catalogue_; hipparcos_catalogue_ = new HipparcosCatalogue(max_magnitude, catalogue_path); hipparcos_catalogue_->IsCalcEnabled = ini_file.ReadEnable(section, CALC_LABEL); - hipparcos_catalogue_->IsLogEnabled = ini_file.ReadEnable(section, LOG_LABEL); + hipparcos_catalogue_->is_log_enabled_ = ini_file.ReadEnable(section, LOG_LABEL); hipparcos_catalogue_->ReadContents(catalogue_path, ','); return hipparcos_catalogue_; @@ -114,7 +114,7 @@ CelestialInformation* InitCelestialInformation(std::string file_name) { celestial_info = new CelestialInformation(inertial_frame, aber_cor, center_obj, rotation_mode, num_of_selected_body, selected_body); // log setting - celestial_info->IsLogEnabled = ini_file.ReadEnable(section, LOG_LABEL); + celestial_info->is_log_enabled_ = ini_file.ReadEnable(section, LOG_LABEL); return celestial_info; } diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 20d325572..f22d1eaf4 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -22,7 +22,7 @@ GeomagneticField InitGeomagneticField(std::string initialize_file_path) { GeomagneticField mag_env(fname, mag_rwdev, mag_rwlimit, mag_wnvar); mag_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); - mag_env.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + mag_env.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); return mag_env; } @@ -34,7 +34,7 @@ SolarRadiationPressureEnvironment InitSolarRadiationPressureEnvironment(std::str SolarRadiationPressureEnvironment srp_env(local_celestial_information); srp_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); - srp_env.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + srp_env.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); return srp_env; } @@ -67,7 +67,7 @@ Atmosphere InitAtmosphere(std::string initialize_file_path) { Atmosphere atmosphere(model, table_path, rho_stddev, is_manual_param_used, manual_daily_f107, manual_average_f107, manual_ap); atmosphere.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); - atmosphere.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); + atmosphere.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); return atmosphere; } diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 73e4d4077..bc4d61fb6 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -45,7 +45,7 @@ void LocalEnvironment::Initialize(const SimulationConfig* simulation_configurati // Log setting for Local celestial information IniAccess conf = IniAccess(ini_fname); - celestial_information_->IsLogEnabled = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); + celestial_information_->is_log_enabled_ = conf.ReadEnable("LOCAL_CELESTIAL_INFORMATION", "logging"); } void LocalEnvironment::Update(const Dynamics* dynamics, const SimulationTime* simulation_time) { diff --git a/src/library/logger/loggable.hpp b/src/library/logger/loggable.hpp index b2ae0e9dd..ab1b22a8b 100644 --- a/src/library/logger/loggable.hpp +++ b/src/library/logger/loggable.hpp @@ -31,7 +31,7 @@ class ILoggable { */ virtual std::string GetLogValue() const = 0; - bool IsLogEnabled = true; //!< Log enable flag + bool is_log_enabled_ = true; //!< Log enable flag }; #endif // S2E_LIBRARY_LOGGER_LOGGABLE_HPP_ diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index 79f8424e5..ad34cde67 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -54,7 +54,7 @@ Logger::~Logger(void) { void Logger::WriteHeaders(bool add_newline) { for (auto itr = loggables_.begin(); itr != loggables_.end(); ++itr) { - if (!((*itr)->IsLogEnabled)) continue; + if (!((*itr)->is_log_enabled_)) continue; Write((*itr)->GetLogHeader()); } if (add_newline) WriteNewLine(); @@ -62,7 +62,7 @@ void Logger::WriteHeaders(bool add_newline) { void Logger::WriteValues(bool add_newline) { for (auto itr = loggables_.begin(); itr != loggables_.end(); ++itr) { - if (!((*itr)->IsLogEnabled)) continue; + if (!((*itr)->is_log_enabled_)) continue; Write((*itr)->GetLogValue()); } if (add_newline) WriteNewLine(); From 46fbff0e1cf5ffcbd2923cccc2ba7f581a643caa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:19:19 +0100 Subject: [PATCH 0640/1086] Remove unused private variables --- src/library/logger/logger.cpp | 1 - src/library/logger/logger.hpp | 1 - 2 files changed, 2 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index ad34cde67..b1dae7390 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -40,7 +40,6 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const is_open_ = csv_file_.is_open(); if (!is_open_) std::cerr << "Error opening log file: " << file_path.str() << std::endl; } - registered_num_ = 0; // Copy SimBase.ini CopyFileToLogDir(ini_file_name); diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index f2ea71868..9e1320f92 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -97,7 +97,6 @@ class Logger { private: std::ofstream csv_file_; //!< CSV file stream - char registered_num_; //!< Number of registered log? (Not used now. TODO: delete?) bool is_enabled_; //!< Enable flag for logging bool is_open_; //!< Is the CSV file opened? std::vector loggables_; //!< Log list From 9e8a5da2f38f95a5e2a0393386e1da65180c61f4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:22:27 +0100 Subject: [PATCH 0641/1086] Move to inline --- src/library/logger/logger.hpp | 22 +++++++++------------- 1 file changed, 9 insertions(+), 13 deletions(-) diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 9e1320f92..bc8c021a0 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -73,27 +73,29 @@ class Logger { */ void WriteNewLine(); - /** - * @fn IsEnabled - * @brief Return enable flag of the log - */ - inline bool IsEnabled(); /** * @fn Enabled * @brief Set enable flag of the log */ - inline void Enable(bool enable); + inline void Enable(bool enable) { is_enabled_ = enable; } /** * @fn CopyFileToLogDir * @brief Copy a file (e.g., ini file) into the log directory * @param [in] ini_file_name: The path to the target file to copy */ void CopyFileToLogDir(const std::string &ini_file_name); + + // Getter + /** + * @fn IsEnabled + * @brief Return enable flag of the log + */ + inline bool IsEnabled() const { return is_enabled_; } /** * @fn GetLogPath * @brief Return the path to the directory for log files */ - inline std::string GetLogPath() const; + inline std::string GetLogPath() const { return directory_path_; } private: std::ofstream csv_file_; //!< CSV file stream @@ -123,10 +125,4 @@ class Logger { std::string GetFileName(const std::string &path); }; -bool Logger::IsEnabled() { return is_enabled_; } - -void Logger::Enable(bool enable) { is_enabled_ = enable; } - -std::string Logger::GetLogPath() const { return directory_path_; } - #endif // S2E_LIBRARY_LOGGER_LOGGER_HPP_ From 7082c5d6a0097b26bcee9d1c20b8924c518e19df Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:28:06 +0100 Subject: [PATCH 0642/1086] Fix private variables name --- src/library/logger/logger.cpp | 14 +++++++------- src/library/logger/logger.hpp | 7 +++---- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index b1dae7390..c3d5320ef 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -17,8 +17,8 @@ std::vector loggables_; Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_inilog, bool enable) { is_enabled_ = enable; - is_open_ = false; - is_enabled_inilog_ = enable_inilog; + is_file_opened_ = false; + is_ini_save_enabled_ = enable_inilog; // Get current time to append it to the filename time_t timer = time(NULL); @@ -28,7 +28,7 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const strftime(start_time_c, 64, "%y%m%d_%H%M%S", now); // Create directory - if (is_enabled_inilog_ == true) + if (is_ini_save_enabled_ == true) directory_path_ = CreateDirectory(data_path, start_time_c); else directory_path_ = data_path; @@ -37,8 +37,8 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const file_path << directory_path_ << start_time_c << "_" << file_name; if (is_enabled_) { csv_file_.open(file_path.str()); - is_open_ = csv_file_.is_open(); - if (!is_open_) std::cerr << "Error opening log file: " << file_path.str() << std::endl; + is_file_opened_ = csv_file_.is_open(); + if (!is_file_opened_) std::cerr << "Error opening log file: " << file_path.str() << std::endl; } // Copy SimBase.ini @@ -46,7 +46,7 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const } Logger::~Logger(void) { - if (is_open_) { + if (is_file_opened_) { csv_file_.close(); } } @@ -99,7 +99,7 @@ std::string Logger::CreateDirectory(const std::string &data_path, const std::str void Logger::CopyFileToLogDir(const std::string &ini_file_name) { using std::ios; - if (is_enabled_inilog_ == false) return; + if (is_ini_save_enabled_ == false) return; // Copy files to the directory std::string file_name = GetFileName(ini_file_name); std::string to_file_name = directory_path_ + file_name; diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index bc8c021a0..7cc875f91 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -100,12 +100,11 @@ class Logger { private: std::ofstream csv_file_; //!< CSV file stream bool is_enabled_; //!< Enable flag for logging - bool is_open_; //!< Is the CSV file opened? + bool is_file_opened_; //!< Is the CSV file opened? std::vector loggables_; //!< Log list - bool is_enabled_inilog_; //!< Enable flag to save ini files - bool is_success_make_dir_ = false; //!< Is success making a directory for log files - std::string directory_path_; //!< Path to the directory for log files + bool is_ini_save_enabled_; //!< Enable flag to save ini files + std::string directory_path_; //!< Path to the directory for log files /** * @fn CreateDirectory From 64686a4c6233e437ea1583e086a80000db9cd27f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:30:29 +0100 Subject: [PATCH 0643/1086] Move to private --- src/library/logger/logger.cpp | 5 +++-- src/library/logger/logger.hpp | 20 +++++++++++--------- 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index c3d5320ef..3e59ef842 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -15,10 +15,11 @@ std::vector loggables_; -Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_inilog, bool enable) { +Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, + bool enable) { is_enabled_ = enable; is_file_opened_ = false; - is_ini_save_enabled_ = enable_inilog; + is_ini_save_enabled_ = enable_ini_file_save; // Get current time to append it to the filename time_t timer = time(NULL); diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 7cc875f91..6a8617385 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -26,23 +26,17 @@ class Logger { * @param [in] file_name: File name of the log output * @param [in] data_path: Path to `data` directory * @param [in] ini_file_name: Initialize file name - * @param [in] enable_inilog: Enable flag to save ini files + * @param [in] enable_ini_file_save: Enable flag to save ini files * @param [in] enable: Enable flag for logging */ - Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_inilog, bool enable = true); + Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, + bool enable = true); /** * @fn ~Logger * @brief Destructor */ ~Logger(void); - /** - * @fn Write - * @brief Write string to the log - * @param [in] log: Write target - * @param [in] flag: Enable flag to write - */ - void Write(std::string log, bool flag = true); /** * @fn AddLoggable * @brief Add a loggable into the log list @@ -106,6 +100,14 @@ class Logger { bool is_ini_save_enabled_; //!< Enable flag to save ini files std::string directory_path_; //!< Path to the directory for log files + /** + * @fn Write + * @brief Write string to the log + * @param [in] log: Write target + * @param [in] flag: Enable flag to write + */ + void Write(std::string log, bool flag = true); + /** * @fn CreateDirectory * @brief Create a directory to store the log files From 590e5cebb8d5a305f8730e0ff5f5f47b90ed1582 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:31:18 +0100 Subject: [PATCH 0644/1086] Move to private --- src/library/logger/logger.hpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 6a8617385..7286b13a3 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -61,11 +61,6 @@ class Logger { * @param add_newline: Add newline or not */ void WriteValues(bool add_newline = true); - /** - * @fn WriteNewline - * @brief Write newline - */ - void WriteNewLine(); /** * @fn Enabled @@ -108,6 +103,12 @@ class Logger { */ void Write(std::string log, bool flag = true); + /** + * @fn WriteNewline + * @brief Write newline + */ + void WriteNewLine(); + /** * @fn CreateDirectory * @brief Create a directory to store the log files From cb5d404d5397e22ca0c7a66e707098197bfe0ba7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:32:04 +0100 Subject: [PATCH 0645/1086] Fix public function name --- src/library/logger/logger.cpp | 2 +- src/library/logger/logger.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index 3e59ef842..4ac3d60b9 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -78,7 +78,7 @@ void Logger::Write(std::string log, bool flag) { void Logger::AddLoggable(ILoggable *loggable) { loggables_.push_back(loggable); } -void Logger::ClearLoggables() { loggables_.clear(); } +void Logger::ClearLogList() { loggables_.clear(); } std::string Logger::CreateDirectory(const std::string &data_path, const std::string &time) { std::string directory_path_tmp_ = data_path + "/logs_" + time + "/"; diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 7286b13a3..d20bd41e8 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -47,7 +47,7 @@ class Logger { * @fn ClearLoggable * @brief Clear the log list */ - void ClearLoggables(); + void ClearLogList(); /** * @fn WriteHeaders From 87f65c2a21e9650d5738efe02946d62e86903212 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:36:44 +0100 Subject: [PATCH 0646/1086] Add const --- src/disturbances/disturbances.cpp | 4 ++-- src/dynamics/dynamics.cpp | 4 ++-- src/environment/global/global_environment.cpp | 4 ++-- src/environment/local/local_environment.cpp | 8 +++---- src/library/logger/logger.cpp | 18 +++++++------- src/library/logger/logger.hpp | 24 +++++++++---------- .../ground_station/ground_station.cpp | 2 +- .../sample_ground_station_components.cpp | 4 ++-- .../relative_information.cpp | 2 +- .../sample_spacecraft/sample_components.cpp | 20 ++++++++-------- 10 files changed, 45 insertions(+), 45 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 6a69b3cb0..faeb85226 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -53,10 +53,10 @@ void Disturbances::Update(const LocalEnvironment& local_environment, const Dynam void Disturbances::LogSetup(Logger& logger) { for (auto dist : disturbances_list_) { - logger.AddLoggable(dist); + logger.AddLogList(dist); } for (auto acc_dist : acceleration_disturbances_list_) { - logger.AddLoggable(acc_dist); + logger.AddLogList(acc_dist); } logger.CopyFileToLogDir(initialize_file_name_); } diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 82483971b..afee0d594 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -65,6 +65,6 @@ void Dynamics::ClearForceTorque(void) { } void Dynamics::LogSetup(Logger& logger) { - logger.AddLoggable(attitude_); - logger.AddLoggable(orbit_); + logger.AddLogList(attitude_); + logger.AddLogList(orbit_); } diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index c6ee8634b..ba264774d 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -41,8 +41,8 @@ void GlobalEnvironment::Update() { } void GlobalEnvironment::LogSetup(Logger& logger) { - logger.AddLoggable(simulation_time_); - logger.AddLoggable(celestial_information_); + logger.AddLogList(simulation_time_); + logger.AddLogList(celestial_information_); } void GlobalEnvironment::Reset(void) { simulation_time_->ResetClock(); } diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index bc4d61fb6..cfde1dc7a 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -68,8 +68,8 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimulationTime* si } void LocalEnvironment::LogSetup(Logger& logger) { - logger.AddLoggable(geomagnetic_field_); - logger.AddLoggable(solar_radiation_pressure_environment_); - logger.AddLoggable(atmosphere_); - logger.AddLoggable(celestial_information_); + logger.AddLogList(geomagnetic_field_); + logger.AddLogList(solar_radiation_pressure_environment_); + logger.AddLogList(atmosphere_); + logger.AddLogList(celestial_information_); } diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index 4ac3d60b9..33a8594cf 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -13,10 +13,10 @@ #include #endif -std::vector loggables_; +std::vector log_list_; Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, - bool enable) { + const bool enable) { is_enabled_ = enable; is_file_opened_ = false; is_ini_save_enabled_ = enable_ini_file_save; @@ -52,16 +52,16 @@ Logger::~Logger(void) { } } -void Logger::WriteHeaders(bool add_newline) { - for (auto itr = loggables_.begin(); itr != loggables_.end(); ++itr) { +void Logger::WriteHeaders(const bool add_newline) { + for (auto itr = log_list_.begin(); itr != log_list_.end(); ++itr) { if (!((*itr)->is_log_enabled_)) continue; Write((*itr)->GetLogHeader()); } if (add_newline) WriteNewLine(); } -void Logger::WriteValues(bool add_newline) { - for (auto itr = loggables_.begin(); itr != loggables_.end(); ++itr) { +void Logger::WriteValues(const bool add_newline) { + for (auto itr = log_list_.begin(); itr != log_list_.end(); ++itr) { if (!((*itr)->is_log_enabled_)) continue; Write((*itr)->GetLogValue()); } @@ -70,15 +70,15 @@ void Logger::WriteValues(bool add_newline) { void Logger::WriteNewLine() { Write("\n"); } -void Logger::Write(std::string log, bool flag) { +void Logger::Write(const std::string log, const bool flag) { if (flag && is_enabled_) { csv_file_ << log; } } -void Logger::AddLoggable(ILoggable *loggable) { loggables_.push_back(loggable); } +void Logger::AddLogList(ILoggable *loggable) { log_list_.push_back(loggable); } -void Logger::ClearLogList() { loggables_.clear(); } +void Logger::ClearLogList() { log_list_.clear(); } std::string Logger::CreateDirectory(const std::string &data_path, const std::string &time) { std::string directory_path_tmp_ = data_path + "/logs_" + time + "/"; diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index d20bd41e8..d6a4b0f0a 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -30,7 +30,7 @@ class Logger { * @param [in] enable: Enable flag for logging */ Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, - bool enable = true); + const bool enable = true); /** * @fn ~Logger * @brief Destructor @@ -38,13 +38,13 @@ class Logger { ~Logger(void); /** - * @fn AddLoggable + * @fn AddLogList * @brief Add a loggable into the log list * @param [in] loggable: loggable */ - void AddLoggable(ILoggable *loggable); + void AddLogList(ILoggable *loggable); /** - * @fn ClearLoggable + * @fn ClearLogList * @brief Clear the log list */ void ClearLogList(); @@ -54,19 +54,19 @@ class Logger { * @brief Write all headers in the log list * @param add_newline: Add newline or not */ - void WriteHeaders(bool add_newline = true); + void WriteHeaders(const bool add_newline = true); /** * @fn WriteValues * @brief Write all values in the log list * @param add_newline: Add newline or not */ - void WriteValues(bool add_newline = true); + void WriteValues(const bool add_newline = true); /** * @fn Enabled * @brief Set enable flag of the log */ - inline void Enable(bool enable) { is_enabled_ = enable; } + inline void Enable(const bool enable) { is_enabled_ = enable; } /** * @fn CopyFileToLogDir * @brief Copy a file (e.g., ini file) into the log directory @@ -87,10 +87,10 @@ class Logger { inline std::string GetLogPath() const { return directory_path_; } private: - std::ofstream csv_file_; //!< CSV file stream - bool is_enabled_; //!< Enable flag for logging - bool is_file_opened_; //!< Is the CSV file opened? - std::vector loggables_; //!< Log list + std::ofstream csv_file_; //!< CSV file stream + bool is_enabled_; //!< Enable flag for logging + bool is_file_opened_; //!< Is the CSV file opened? + std::vector log_list_; //!< Log list bool is_ini_save_enabled_; //!< Enable flag to save ini files std::string directory_path_; //!< Path to the directory for log files @@ -101,7 +101,7 @@ class Logger { * @param [in] log: Write target * @param [in] flag: Enable flag to write */ - void Write(std::string log, bool flag = true); + void Write(const std::string log, const bool flag = true); /** * @fn WriteNewline diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index dd0b09717..989bfce29 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -42,7 +42,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { config->main_logger_->CopyFileToLogDir(gs_ini_path); } -void GroundStation::LogSetup(Logger& logger) { logger.AddLoggable(this); } +void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft) { Matrix<3, 3> dcm_ecef2eci = transpose(celes_rotation.GetDcmJ2000ToXcxf()); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 228a318e7..b049ac008 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -23,6 +23,6 @@ SampleGSComponents::~SampleGSComponents() { } void SampleGSComponents::CompoLogSetUp(Logger& logger) { - // logger.AddLoggable(ant_); - logger.AddLoggable(gs_calculator_); + // logger.AddLogList(ant_); + logger.AddLogList(gs_calculator_); } diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index ee5c76eeb..4047375b7 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -101,7 +101,7 @@ std::string RelativeInformation::GetLogValue() const { return str_tmp; } -void RelativeInformation::LogSetup(Logger& logger) { logger.AddLoggable(this); } +void RelativeInformation::LogSetup(Logger& logger) { logger.AddLogList(this); } libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int target_sat_id, const int reference_sat_id) { // Observer SC Body frame(obs_sat) -> ECI frame(i) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index d5f82bb6f..964b285f2 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -166,14 +166,14 @@ libra::Vector<3> SampleComponents::GenerateTorque_Nm_b() { } void SampleComponents::LogSetup(Logger& logger) { - logger.AddLoggable(gyro_); - logger.AddLoggable(mag_sensor_); - logger.AddLoggable(stt_); - logger.AddLoggable(sun_sensor_); - logger.AddLoggable(gnss_); - logger.AddLoggable(mag_torquer_); - logger.AddLoggable(rw_); - logger.AddLoggable(thruster_); - logger.AddLoggable(force_generator_); - logger.AddLoggable(torque_generator_); + logger.AddLogList(gyro_); + logger.AddLogList(mag_sensor_); + logger.AddLogList(stt_); + logger.AddLogList(sun_sensor_); + logger.AddLogList(gnss_); + logger.AddLogList(mag_torquer_); + logger.AddLogList(rw_); + logger.AddLogList(thruster_); + logger.AddLogList(force_generator_); + logger.AddLogList(torque_generator_); } From 320272dd4d21b43c3dc054f1aa34cc49bf2022c4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:37:48 +0100 Subject: [PATCH 0647/1086] Fix public function name --- src/disturbances/disturbances.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/library/logger/logger.cpp | 4 ++-- src/library/logger/logger.hpp | 4 ++-- .../ground_station/ground_station.cpp | 2 +- .../sample_ground_station_components.cpp | 4 ++-- .../sample_spacecraft/sample_components.cpp | 22 +++++++++---------- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- .../spacecraft/structure/structure.cpp | 2 +- 9 files changed, 23 insertions(+), 23 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index faeb85226..a9a7e3d2f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -58,7 +58,7 @@ void Disturbances::LogSetup(Logger& logger) { for (auto acc_dist : acceleration_disturbances_list_) { logger.AddLogList(acc_dist); } - logger.CopyFileToLogDir(initialize_file_name_); + logger.CopyFileToLogDirectory(initialize_file_name_); } void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index cfde1dc7a..b79741d1e 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -28,7 +28,7 @@ void LocalEnvironment::Initialize(const SimulationConfig* simulation_configurati std::string ini_fname = iniAccess.ReadString("SETTING_FILES", "local_environment_file"); // Save ini file - simulation_configuration->main_logger_->CopyFileToLogDir(ini_fname); + simulation_configuration->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize geomagnetic_field_ = new GeomagneticField(InitGeomagneticField(ini_fname)); diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index 33a8594cf..a15e64827 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -43,7 +43,7 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const } // Copy SimBase.ini - CopyFileToLogDir(ini_file_name); + CopyFileToLogDirectory(ini_file_name); } Logger::~Logger(void) { @@ -97,7 +97,7 @@ std::string Logger::CreateDirectory(const std::string &data_path, const std::str return directory_path_tmp_; } -void Logger::CopyFileToLogDir(const std::string &ini_file_name) { +void Logger::CopyFileToLogDirectory(const std::string &ini_file_name) { using std::ios; if (is_ini_save_enabled_ == false) return; diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index d6a4b0f0a..827daa4c2 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -68,11 +68,11 @@ class Logger { */ inline void Enable(const bool enable) { is_enabled_ = enable; } /** - * @fn CopyFileToLogDir + * @fn CopyFileToLogDirectory * @brief Copy a file (e.g., ini file) into the log directory * @param [in] ini_file_name: The path to the target file to copy */ - void CopyFileToLogDir(const std::string &ini_file_name); + void CopyFileToLogDirectory(const std::string &ini_file_name); // Getter /** diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 989bfce29..db8edf931 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -39,7 +39,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { elevation_limit_angle_deg_ = conf.ReadDouble(Section, "elevation_limit_angle_deg"); - config->main_logger_->CopyFileToLogDir(gs_ini_path); + config->main_logger_->CopyFileToLogDirectory(gs_ini_path); } void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index b049ac008..e4b16cf96 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -10,10 +10,10 @@ SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_ IniAccess iniAccess = IniAccess(config_->gs_file_); std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); - config_->main_logger_->CopyFileToLogDir(ant_ini_path); + config_->main_logger_->CopyFileToLogDirectory(ant_ini_path); antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); - config_->main_logger_->CopyFileToLogDir(gscalculator_ini_path); + config_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); gs_calculator_ = new GScalculator(InitGScalculator(gscalculator_ini_path)); } diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 964b285f2..5241b14fa 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -26,63 +26,63 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Gyro std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // MagSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); mag_sensor_ = new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); // STT ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); stt_ = new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_env_->GetSolarRadiationPressure()), &(local_env_->GetCelestialInformation()))); // GNSS-R ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); gnss_ = new GNSSReceiver( InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); // MagTorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); mag_torquer_ = new MagTorquer(InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); rw_ = new RWModel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), glo_env_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_gen, ini_path, dynamics_)); // Thruster ini_path = iniAccess.ReadString("COMPONENT_FILES", "thruster_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); thruster_ = new SimpleThruster(InitSimpleThruster(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, structure_, dynamics)); // Force Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "force_generator_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_gen, ini_path, dynamics_)); // Antenna ini_path = iniAccess.ReadString("COMPONENT_FILES", "antenna_file"); - config_->main_logger_->CopyFileToLogDir(ini_path); + config_->main_logger_->CopyFileToLogDirectory(ini_path); antenna_ = new Antenna(InitAntenna(1, ini_path)); // PCU power port initial control diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 297a3df6c..8aff1967e 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -35,7 +35,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); - sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); + sim_config->main_logger_->CopyFileToLogDirectory(sim_config->sat_file_[sat_id]); rel_info_ = nullptr; } @@ -47,7 +47,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_, rel_info); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); - sim_config->main_logger_->CopyFileToLogDir(sim_config->sat_file_[sat_id]); + sim_config->main_logger_->CopyFileToLogDirectory(sim_config->sat_file_[sat_id]); rel_info_ = rel_info; rel_info_->RegisterDynamicsInfo(sat_id, dynamics_); diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 25214c210..2b1b3f661 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -20,7 +20,7 @@ void Structure::Initialize(SimulationConfig* sim_config, const int sat_id) { IniAccess conf = IniAccess(sim_config->sat_file_[sat_id]); std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); // Save ini file - sim_config->main_logger_->CopyFileToLogDir(ini_fname); + sim_config->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize kinnematics_params_ = new KinematicsParams(InitKinematicsParams(ini_fname)); surfaces_ = InitSurfaces(ini_fname); From 9806a24ae6613cfb44860fc3a74403acfa9db6c8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:40:26 +0100 Subject: [PATCH 0648/1086] Fix public function name --- src/library/logger/initialize_log.cpp | 2 +- src/library/logger/initialize_log.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/library/logger/initialize_log.cpp b/src/library/logger/initialize_log.cpp index 5bf20637f..598f2f475 100644 --- a/src/library/logger/initialize_log.cpp +++ b/src/library/logger/initialize_log.cpp @@ -18,7 +18,7 @@ Logger* InitLog(std::string file_name) { return log; } -Logger* InitLogMC(std::string file_name, bool enable) { +Logger* InitMonteCarloLog(std::string file_name, bool enable) { IniAccess ini_file(file_name); std::string log_file_path = ini_file.ReadString("SIMULATION_SETTINGS", "log_file_save_directory"); diff --git a/src/library/logger/initialize_log.hpp b/src/library/logger/initialize_log.hpp index 4dd64a836..2f683bb83 100644 --- a/src/library/logger/initialize_log.hpp +++ b/src/library/logger/initialize_log.hpp @@ -16,11 +16,11 @@ Logger* InitLog(std::string file_name); /** - * @fn InitLogMC + * @fn InitMonteCarloLog * @brief Initialize logger for Monte-Carlo simulation (mont.csv) * @param [in] file_name: File name of the log file * @param [in] enable: Enable flag for logging */ -Logger* InitLogMC(std::string file_name, bool enable); +Logger* InitMonteCarloLog(std::string file_name, bool enable); #endif // S2E_LIBRARY_LOGGER_INITIALIZE_LOG_HPP_ From 35c0f6417861f6af15d9fac0c4f84d303e98af80 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:44:17 +0100 Subject: [PATCH 0649/1086] Fix private variables --- src/library/optics/gaussian_beam_base.cpp | 14 +++++++------- src/library/optics/gaussian_beam_base.hpp | 16 ++++++++-------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/library/optics/gaussian_beam_base.cpp b/src/library/optics/gaussian_beam_base.cpp index e54115ebc..0329992cf 100644 --- a/src/library/optics/gaussian_beam_base.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -9,7 +9,7 @@ #include GaussianBeamBase::GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt) - : wavelength_m_(wavelength_m), r_beam_waist_m_(r_beam_waist_m), total_power_watt_(total_power_watt) {} + : wavelength_m_(wavelength_m), radius_beam_waist_m_(r_beam_waist_m), total_power_W_(total_power_watt) {} GaussianBeamBase::~GaussianBeamBase() {} @@ -20,27 +20,27 @@ void GaussianBeamBase::SetWaveLength(const double wavelength_m) { void GaussianBeamBase::SetBeamWaistRadius(const double r_beam_waist_m) { assert(r_beam_waist_m > 0.0); - r_beam_waist_m_ = r_beam_waist_m; + radius_beam_waist_m_ = r_beam_waist_m; } void GaussianBeamBase::SetTotalPower(const double total_power_watt) { assert(total_power_watt >= 0.0); - total_power_watt_ = total_power_watt; + total_power_W_ = total_power_watt; } void GaussianBeamBase::SetPointingVector_i(const libra::Vector<3> pointing_vector_i) { pointing_vector_i_ = pointing_vector_i; } -void GaussianBeamBase::SetBeamWaistPos_i(const libra::Vector<3> pos_beamwaist_i) { pos_beamwaist_i_ = pos_beamwaist_i; } +void GaussianBeamBase::SetBeamWaistPos_i(const libra::Vector<3> pos_beamwaist_i) { position_beam_waist_i_m_ = pos_beamwaist_i; } double GaussianBeamBase::CalcBeamWidthRadius(double distance_from_beamwaist_m) { - double rayleigh_length_m = libra::pi * r_beam_waist_m_ * r_beam_waist_m_ / wavelength_m_; - double beam_width_radius_m = r_beam_waist_m_ * sqrt(1.0 + std::pow((distance_from_beamwaist_m / rayleigh_length_m), 2.0)); + double rayleigh_length_m = libra::pi * radius_beam_waist_m_ * radius_beam_waist_m_ / wavelength_m_; + double beam_width_radius_m = radius_beam_waist_m_ * sqrt(1.0 + std::pow((distance_from_beamwaist_m / rayleigh_length_m), 2.0)); return beam_width_radius_m; } double GaussianBeamBase::CalcIntensity(double distance_from_beamwaist_m, double deviation_from_optical_axis_m) { double beam_width_radius_m = CalcBeamWidthRadius(distance_from_beamwaist_m); - double peak_intensity_watt_m2 = (2.0 * total_power_watt_) / (libra::pi * beam_width_radius_m * beam_width_radius_m); + double peak_intensity_watt_m2 = (2.0 * total_power_W_) / (libra::pi * beam_width_radius_m * beam_width_radius_m); double gaussian_dist = std::exp((-2.0 * deviation_from_optical_axis_m * deviation_from_optical_axis_m) / (beam_width_radius_m * beam_width_radius_m)); double intensity_watt_m2 = peak_intensity_watt_m2 * gaussian_dist; diff --git a/src/library/optics/gaussian_beam_base.hpp b/src/library/optics/gaussian_beam_base.hpp index 5d56375d4..3259a491b 100644 --- a/src/library/optics/gaussian_beam_base.hpp +++ b/src/library/optics/gaussian_beam_base.hpp @@ -65,12 +65,12 @@ class GaussianBeamBase { * @fn GetBeamWaistRadius * @brief Return radius of beam waist [m] */ - inline double GetBeamWaistRadius() const { return r_beam_waist_m_; } + inline double GetBeamWaistRadius() const { return radius_beam_waist_m_; } /** * @fn GetTotalPower * @brief Return total power [W] */ - inline double GetTotalPower() const { return total_power_watt_; } + inline double GetTotalPower() const { return total_power_W_; } /** * @fn GetPointingVector_i * @brief Return pointing direction vector in the inertial frame @@ -80,7 +80,7 @@ class GaussianBeamBase { * @fn GetBeamWaistPos_i * @brief Return position of beam waist in the inertial frame [m] (Not used?) */ - inline const libra::Vector<3> GetBeamWaistPos_i() const { return pos_beamwaist_i_; } + inline const libra::Vector<3> GetBeamWaistPos_i() const { return position_beam_waist_i_m_; } // Calculate functions /** @@ -100,11 +100,11 @@ class GaussianBeamBase { double CalcIntensity(double distance_from_beamwaist_m, double deviation_from_optical_axis_m); private: - double wavelength_m_; //!< Wavelength [m] - double r_beam_waist_m_; //!< Radius of beam waist [m] - double total_power_watt_; //!< Total power [W] - libra::Vector<3> pointing_vector_i_{0.0}; //!< Pointing direction vector in the inertial frame - libra::Vector<3> pos_beamwaist_i_{0.0}; //!< Position of beam waist in the inertial frame [m] (Not used?) + double wavelength_m_; //!< Wavelength [m] + double radius_beam_waist_m_; //!< Radius of beam waist [m] + double total_power_W_; //!< Total power [W] + libra::Vector<3> pointing_vector_i_{0.0}; //!< Pointing direction vector in the inertial frame + libra::Vector<3> position_beam_waist_i_m_{0.0}; //!< Position of beam waist in the inertial frame [m] (Not used?) }; #endif // S2E_LIBRARY_OPTICS_GAUSSIAN_BEAM_BASE_HPP_ From 23dd52512aab06671ee33f89faec11b79a073477 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:46:33 +0100 Subject: [PATCH 0650/1086] Fix function argument names --- src/library/optics/gaussian_beam_base.cpp | 26 +++++++++++------------ src/library/optics/gaussian_beam_base.hpp | 20 ++++++++--------- 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/src/library/optics/gaussian_beam_base.cpp b/src/library/optics/gaussian_beam_base.cpp index 0329992cf..c862f7a3a 100644 --- a/src/library/optics/gaussian_beam_base.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -8,8 +8,8 @@ #include #include -GaussianBeamBase::GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt) - : wavelength_m_(wavelength_m), radius_beam_waist_m_(r_beam_waist_m), total_power_W_(total_power_watt) {} +GaussianBeamBase::GaussianBeamBase(double wavelength_m, double radius_beam_waist_m, double total_power_W) + : wavelength_m_(wavelength_m), radius_beam_waist_m_(radius_beam_waist_m), total_power_W_(total_power_W) {} GaussianBeamBase::~GaussianBeamBase() {} @@ -18,28 +18,28 @@ void GaussianBeamBase::SetWaveLength(const double wavelength_m) { wavelength_m_ = wavelength_m; } -void GaussianBeamBase::SetBeamWaistRadius(const double r_beam_waist_m) { - assert(r_beam_waist_m > 0.0); - radius_beam_waist_m_ = r_beam_waist_m; +void GaussianBeamBase::SetBeamWaistRadius(const double radius_beam_waist_m) { + assert(radius_beam_waist_m > 0.0); + radius_beam_waist_m_ = radius_beam_waist_m; } -void GaussianBeamBase::SetTotalPower(const double total_power_watt) { - assert(total_power_watt >= 0.0); - total_power_W_ = total_power_watt; +void GaussianBeamBase::SetTotalPower(const double total_power_W) { + assert(total_power_W >= 0.0); + total_power_W_ = total_power_W; } void GaussianBeamBase::SetPointingVector_i(const libra::Vector<3> pointing_vector_i) { pointing_vector_i_ = pointing_vector_i; } -void GaussianBeamBase::SetBeamWaistPos_i(const libra::Vector<3> pos_beamwaist_i) { position_beam_waist_i_m_ = pos_beamwaist_i; } +void GaussianBeamBase::SetBeamWaistPos_i(const libra::Vector<3> position_beam_waist_i_m) { position_beam_waist_i_m_ = position_beam_waist_i_m; } -double GaussianBeamBase::CalcBeamWidthRadius(double distance_from_beamwaist_m) { +double GaussianBeamBase::CalcBeamWidthRadius(double distance_from_beam_waist_m) { double rayleigh_length_m = libra::pi * radius_beam_waist_m_ * radius_beam_waist_m_ / wavelength_m_; - double beam_width_radius_m = radius_beam_waist_m_ * sqrt(1.0 + std::pow((distance_from_beamwaist_m / rayleigh_length_m), 2.0)); + double beam_width_radius_m = radius_beam_waist_m_ * sqrt(1.0 + std::pow((distance_from_beam_waist_m / rayleigh_length_m), 2.0)); return beam_width_radius_m; } -double GaussianBeamBase::CalcIntensity(double distance_from_beamwaist_m, double deviation_from_optical_axis_m) { - double beam_width_radius_m = CalcBeamWidthRadius(distance_from_beamwaist_m); +double GaussianBeamBase::CalcIntensity(double distance_from_beam_waist_m, double deviation_from_optical_axis_m) { + double beam_width_radius_m = CalcBeamWidthRadius(distance_from_beam_waist_m); double peak_intensity_watt_m2 = (2.0 * total_power_W_) / (libra::pi * beam_width_radius_m * beam_width_radius_m); double gaussian_dist = std::exp((-2.0 * deviation_from_optical_axis_m * deviation_from_optical_axis_m) / (beam_width_radius_m * beam_width_radius_m)); diff --git a/src/library/optics/gaussian_beam_base.hpp b/src/library/optics/gaussian_beam_base.hpp index 3259a491b..402547e4b 100644 --- a/src/library/optics/gaussian_beam_base.hpp +++ b/src/library/optics/gaussian_beam_base.hpp @@ -18,10 +18,10 @@ class GaussianBeamBase { * @fn GaussianBeamBase * @brief Constructor * @param [in] wavelength_m: Wavelength [m] - * @param [in] r_beam_waist_m: Radius of beam waist [m] - * @param [in] total_power_watt: Total power [W] + * @param [in] radius_beam_waist_m: Radius of beam waist [m] + * @param [in] total_power_W: Total power [W] */ - GaussianBeamBase(double wavelength_m, double r_beam_waist_m, double total_power_watt); + GaussianBeamBase(double wavelength_m, double radius_beam_waist_m, double total_power_W); /** * @fn ~GaussianBeamBase * @brief Destructor @@ -38,12 +38,12 @@ class GaussianBeamBase { * @fn SetBeamWaistRadius * @brief Set radius of beam waist [m] */ - void SetBeamWaistRadius(const double r_beam_waist_m); + void SetBeamWaistRadius(const double radius_beam_waist_m); /** * @fn SetTotalPower * @brief Set total power [W] */ - void SetTotalPower(const double total_power_watt); + void SetTotalPower(const double total_power_W); /** * @fn SetPointingVector_i * @brief Set pointing direction vector in the inertial frame @@ -53,7 +53,7 @@ class GaussianBeamBase { * @fn SetBeamWaistPos_i * @brief Set position of beam waist in the inertial frame [m] (Not used?) */ - void SetBeamWaistPos_i(const libra::Vector<3> pos_beamwaist_i); + void SetBeamWaistPos_i(const libra::Vector<3> position_beam_waist_i_m); // Getter /** @@ -86,18 +86,18 @@ class GaussianBeamBase { /** * @fn CalcBeamWidthRadius * @brief - * @param [in] distance_from_beamwaist_m: Distance from beamwaist [m] + * @param [in] distance_from_beam_waist_m: Distance from beam waist [m] * @return Beam width radius */ - double CalcBeamWidthRadius(double distance_from_beamwaist_m); + double CalcBeamWidthRadius(double distance_from_beam_waist_m); /** * @fn CalcIntensity * @brief - * @param [in] distance_from_beamwaist_m: Distance from beamwaist [m] + * @param [in] distance_from_beam_waist_m: Distance from beam waist [m] * @param [in] deviation_from_optical_axis_m: Deviation from optical axis [m] * @return Intensity */ - double CalcIntensity(double distance_from_beamwaist_m, double deviation_from_optical_axis_m); + double CalcIntensity(double distance_from_beam_waist_m, double deviation_from_optical_axis_m); private: double wavelength_m_; //!< Wavelength [m] From 2f3fe1e64e9d1b30c2a4e282ed345b53c14b2bfd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:50:40 +0100 Subject: [PATCH 0651/1086] Fix public function names --- src/library/optics/gaussian_beam_base.cpp | 22 ++++++------ src/library/optics/gaussian_beam_base.hpp | 44 +++++++++++------------ 2 files changed, 34 insertions(+), 32 deletions(-) diff --git a/src/library/optics/gaussian_beam_base.cpp b/src/library/optics/gaussian_beam_base.cpp index c862f7a3a..3f181c0b0 100644 --- a/src/library/optics/gaussian_beam_base.cpp +++ b/src/library/optics/gaussian_beam_base.cpp @@ -13,36 +13,38 @@ GaussianBeamBase::GaussianBeamBase(double wavelength_m, double radius_beam_waist GaussianBeamBase::~GaussianBeamBase() {} -void GaussianBeamBase::SetWaveLength(const double wavelength_m) { +void GaussianBeamBase::SetWaveLength_m(const double wavelength_m) { assert(wavelength_m > 0.0); wavelength_m_ = wavelength_m; } -void GaussianBeamBase::SetBeamWaistRadius(const double radius_beam_waist_m) { +void GaussianBeamBase::SetBeamWaistRadius_m(const double radius_beam_waist_m) { assert(radius_beam_waist_m > 0.0); radius_beam_waist_m_ = radius_beam_waist_m; } -void GaussianBeamBase::SetTotalPower(const double total_power_W) { +void GaussianBeamBase::SetTotalPower_W(const double total_power_W) { assert(total_power_W >= 0.0); total_power_W_ = total_power_W; } void GaussianBeamBase::SetPointingVector_i(const libra::Vector<3> pointing_vector_i) { pointing_vector_i_ = pointing_vector_i; } -void GaussianBeamBase::SetBeamWaistPos_i(const libra::Vector<3> position_beam_waist_i_m) { position_beam_waist_i_m_ = position_beam_waist_i_m; } +void GaussianBeamBase::SetBeamWaistPosition_i_m(const libra::Vector<3> position_beam_waist_i_m) { + position_beam_waist_i_m_ = position_beam_waist_i_m; +} -double GaussianBeamBase::CalcBeamWidthRadius(double distance_from_beam_waist_m) { +double GaussianBeamBase::CalcBeamWidthRadius_m(double distance_from_beam_waist_m) { double rayleigh_length_m = libra::pi * radius_beam_waist_m_ * radius_beam_waist_m_ / wavelength_m_; double beam_width_radius_m = radius_beam_waist_m_ * sqrt(1.0 + std::pow((distance_from_beam_waist_m / rayleigh_length_m), 2.0)); return beam_width_radius_m; } -double GaussianBeamBase::CalcIntensity(double distance_from_beam_waist_m, double deviation_from_optical_axis_m) { - double beam_width_radius_m = CalcBeamWidthRadius(distance_from_beam_waist_m); - double peak_intensity_watt_m2 = (2.0 * total_power_W_) / (libra::pi * beam_width_radius_m * beam_width_radius_m); +double GaussianBeamBase::CalcIntensity_W_m2(double distance_from_beam_waist_m, double deviation_from_optical_axis_m) { + double beam_width_radius_m = CalcBeamWidthRadius_m(distance_from_beam_waist_m); + double peak_intensity_W_m2 = (2.0 * total_power_W_) / (libra::pi * beam_width_radius_m * beam_width_radius_m); double gaussian_dist = std::exp((-2.0 * deviation_from_optical_axis_m * deviation_from_optical_axis_m) / (beam_width_radius_m * beam_width_radius_m)); - double intensity_watt_m2 = peak_intensity_watt_m2 * gaussian_dist; - return intensity_watt_m2; + double intensity_W_m2 = peak_intensity_W_m2 * gaussian_dist; + return intensity_W_m2; } diff --git a/src/library/optics/gaussian_beam_base.hpp b/src/library/optics/gaussian_beam_base.hpp index 402547e4b..e47e98428 100644 --- a/src/library/optics/gaussian_beam_base.hpp +++ b/src/library/optics/gaussian_beam_base.hpp @@ -30,74 +30,74 @@ class GaussianBeamBase { // Setter /** - * @fn SetWaveLength + * @fn SetWaveLength_m * @brief Set wavelength [m] */ - void SetWaveLength(const double wavelength_m); + void SetWaveLength_m(const double wavelength_m); /** - * @fn SetBeamWaistRadius + * @fn SetBeamWaistRadius_m * @brief Set radius of beam waist [m] */ - void SetBeamWaistRadius(const double radius_beam_waist_m); + void SetBeamWaistRadius_m(const double radius_beam_waist_m); /** - * @fn SetTotalPower + * @fn SetTotalPower_W * @brief Set total power [W] */ - void SetTotalPower(const double total_power_W); + void SetTotalPower_W(const double total_power_W); /** * @fn SetPointingVector_i * @brief Set pointing direction vector in the inertial frame */ void SetPointingVector_i(const libra::Vector<3> pointing_vector_i); /** - * @fn SetBeamWaistPos_i + * @fn SetBeamWaistPosition_i_m * @brief Set position of beam waist in the inertial frame [m] (Not used?) */ - void SetBeamWaistPos_i(const libra::Vector<3> position_beam_waist_i_m); + void SetBeamWaistPosition_i_m(const libra::Vector<3> position_beam_waist_i_m); // Getter /** - * @fn GetWaveLength + * @fn GetWaveLength_m * @brief Return wavelength [m] */ - inline double GetWaveLength() const { return wavelength_m_; } + inline double GetWaveLength_m() const { return wavelength_m_; } /** - * @fn GetBeamWaistRadius + * @fn GetBeamWaistRadius_m * @brief Return radius of beam waist [m] */ - inline double GetBeamWaistRadius() const { return radius_beam_waist_m_; } + inline double GetBeamWaistRadius_m() const { return radius_beam_waist_m_; } /** - * @fn GetTotalPower + * @fn GetTotalPower_W * @brief Return total power [W] */ - inline double GetTotalPower() const { return total_power_W_; } + inline double GetTotalPower_W() const { return total_power_W_; } /** * @fn GetPointingVector_i * @brief Return pointing direction vector in the inertial frame */ inline const libra::Vector<3> GetPointingVector_i() const { return pointing_vector_i_; } /** - * @fn GetBeamWaistPos_i + * @fn GetBeamWaistPosition_i_m * @brief Return position of beam waist in the inertial frame [m] (Not used?) */ - inline const libra::Vector<3> GetBeamWaistPos_i() const { return position_beam_waist_i_m_; } + inline const libra::Vector<3> GetBeamWaistPosition_i_m() const { return position_beam_waist_i_m_; } // Calculate functions /** - * @fn CalcBeamWidthRadius + * @fn CalcBeamWidthRadius_m * @brief * @param [in] distance_from_beam_waist_m: Distance from beam waist [m] - * @return Beam width radius + * @return Beam width radius [m] */ - double CalcBeamWidthRadius(double distance_from_beam_waist_m); + double CalcBeamWidthRadius_m(double distance_from_beam_waist_m); /** - * @fn CalcIntensity + * @fn CalcIntensity_W_m2 * @brief * @param [in] distance_from_beam_waist_m: Distance from beam waist [m] * @param [in] deviation_from_optical_axis_m: Deviation from optical axis [m] - * @return Intensity + * @return Intensity [W/m2] */ - double CalcIntensity(double distance_from_beam_waist_m, double deviation_from_optical_axis_m); + double CalcIntensity_W_m2(double distance_from_beam_waist_m, double deviation_from_optical_axis_m); private: double wavelength_m_; //!< Wavelength [m] From 781c1b489066ed44afa961a62c03b93ae8e5d9b2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:53:48 +0100 Subject: [PATCH 0652/1086] Fix public function names --- src/library/orbit/kepler_orbit.cpp | 12 ++++++------ src/library/orbit/orbital_elements.hpp | 20 ++++++++++---------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/library/orbit/kepler_orbit.cpp b/src/library/orbit/kepler_orbit.cpp index f26b170ee..59dcdadea 100644 --- a/src/library/orbit/kepler_orbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -16,23 +16,23 @@ KeplerOrbit::~KeplerOrbit() {} // Private Functions void KeplerOrbit::CalcConstKeplerMotion() { // mean motion - double a_m3 = pow(oe_.GetSemiMajor(), 3.0); + double a_m3 = pow(oe_.GetSemiMajorAxis_m(), 3.0); mean_motion_rad_s_ = sqrt(mu_m3_s2_ / a_m3); // DCM - libra::Matrix<3, 3> dcm_arg_perigee = libra::rotz(-1.0 * oe_.GetArgPerigee()); - libra::Matrix<3, 3> dcm_inclination = libra::rotx(-1.0 * oe_.GetInclination()); - libra::Matrix<3, 3> dcm_raan = libra::rotz(-1.0 * oe_.GetRaan()); + libra::Matrix<3, 3> dcm_arg_perigee = libra::rotz(-1.0 * oe_.GetArgPerigee_rad()); + libra::Matrix<3, 3> dcm_inclination = libra::rotx(-1.0 * oe_.GetInclination_rad()); + libra::Matrix<3, 3> dcm_raan = libra::rotz(-1.0 * oe_.GetRaan_rad()); libra::Matrix<3, 3> dcm_inc_arg = dcm_inclination * dcm_arg_perigee; dcm_inplane_to_i_ = dcm_raan * dcm_inc_arg; } void KeplerOrbit::CalcPosVel(double time_jday) { // replace to short name variables - double a_m = oe_.GetSemiMajor(); + double a_m = oe_.GetSemiMajorAxis_m(); double e = oe_.GetEccentricity(); double n_rad_s = mean_motion_rad_s_; - double dt_s = (time_jday - oe_.GetEpoch()) * (24.0 * 60.0 * 60.0); + double dt_s = (time_jday - oe_.GetEpoch_jday()) * (24.0 * 60.0 * 60.0); double mean_anomaly_rad = mean_motion_rad_s_ * dt_s; double l_rad = libra::WrapTo2Pi(mean_anomaly_rad); diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index d78d424d8..92167d42f 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -48,35 +48,35 @@ class OrbitalElements { // Getter /** - * @fn GetSemiMajor + * @fn GetSemiMajorAxis_m * @brief Return semi major axis [m] */ - inline double GetSemiMajor() const { return semi_major_axis_m_; } + inline double GetSemiMajorAxis_m() const { return semi_major_axis_m_; } /** * @fn GetEccentricity * @brief Return eccentricity */ inline double GetEccentricity() const { return eccentricity_; } /** - * @fn GetInclination + * @fn GetInclination_rad * @brief Return inclination [rad] */ - inline double GetInclination() const { return inclination_rad_; } + inline double GetInclination_rad() const { return inclination_rad_; } /** - * @fn GetRaan + * @fn GetRaan_rad * @brief Return Right Ascension of the Ascending Node [rad] */ - inline double GetRaan() const { return raan_rad_; } + inline double GetRaan_rad() const { return raan_rad_; } /** - * @fn GetArgPerigee + * @fn GetArgPerigee_rad * @brief Return argument of Perigee [rad] */ - inline double GetArgPerigee() const { return arg_perigee_rad_; } + inline double GetArgPerigee_rad() const { return arg_perigee_rad_; } /** - * @fn GetEpoch + * @fn GetEpoch_jday * @brief Return epoch (time at the perigee) [julian day] */ - inline double GetEpoch() const { return epoch_jday_; } + inline double GetEpoch_jday() const { return epoch_jday_; } private: // Common Variables From a1c01d684cb041af1de62558b4f2addff96359bd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 15:57:53 +0100 Subject: [PATCH 0653/1086] Fix private function --- src/library/orbit/orbital_elements.cpp | 21 +++++++++++---------- src/library/orbit/orbital_elements.hpp | 11 +++++++++-- 2 files changed, 20 insertions(+), 12 deletions(-) diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index 7ae918e52..146a802b5 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -30,12 +30,13 @@ OrbitalElements::OrbitalElements(const double mu_m3_s2, const double time_jday, OrbitalElements::~OrbitalElements() {} // Private Function -void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> r_i_m, const libra::Vector<3> v_i_m_s) { +void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, + const libra::Vector<3> velocity_i_m_s) { // common variables - double r_m = norm(r_i_m); - double v2_m2_s2 = inner_product(v_i_m_s, v_i_m_s); + double r_m = norm(position_i_m); + double v2_m2_s2 = inner_product(velocity_i_m_s, velocity_i_m_s); libra::Vector<3> h; - h = outer_product(r_i_m, v_i_m_s); + h = outer_product(position_i_m, velocity_i_m_s); double h_norm = norm(h); // semi major axis @@ -55,14 +56,14 @@ void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_ raan_rad_ = asin(h[0] / sqrt(h[0] * h[0] + h[1] * h[1])); } // position in plane - double x_p_m = r_i_m[0] * cos(raan_rad_) + r_i_m[1] * sin(raan_rad_); - double tmp_m = -r_i_m[0] * sin(raan_rad_) + r_i_m[1] * cos(raan_rad_); - double y_p_m = tmp_m * cos(inclination_rad_) + r_i_m[2] * sin(inclination_rad_); + double x_p_m = position_i_m[0] * cos(raan_rad_) + position_i_m[1] * sin(raan_rad_); + double tmp_m = -position_i_m[0] * sin(raan_rad_) + position_i_m[1] * cos(raan_rad_); + double y_p_m = tmp_m * cos(inclination_rad_) + position_i_m[2] * sin(inclination_rad_); // velocity in plane - double dx_p_m_s = v_i_m_s[0] * cos(raan_rad_) + v_i_m_s[1] * sin(raan_rad_); - double dtmp_m_s = -v_i_m_s[0] * sin(raan_rad_) + v_i_m_s[1] * cos(raan_rad_); - double dy_p_m_s = dtmp_m_s * cos(inclination_rad_) + v_i_m_s[2] * sin(inclination_rad_); + double dx_p_m_s = velocity_i_m_s[0] * cos(raan_rad_) + velocity_i_m_s[1] * sin(raan_rad_); + double dtmp_m_s = -velocity_i_m_s[0] * sin(raan_rad_) + velocity_i_m_s[1] * cos(raan_rad_); + double dy_p_m_s = dtmp_m_s * cos(inclination_rad_) + velocity_i_m_s[2] * sin(inclination_rad_); // eccentricity double t1 = (h_norm / mu_m3_s2) * dy_p_m_s - x_p_m / r_m; diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index 92167d42f..1ac4cb591 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -91,8 +91,15 @@ class OrbitalElements { double epoch_jday_; //!< epoch (time at the perigee) [julian day] // Functions - // Calculation of Orbital Elements from Position and Velocity - void CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> r_i_m, const libra::Vector<3> v_i_m_s); + /** + * @fn CalcOeFromPosVel + * @brief Calculation of Orbital Elements from Position and Velocity + * @param[in] mu_m3_s2: Gravity Constant of the center body + * @param[in] time_jday: Time expressed as Julian day + * @param[in] position_i_m: Position vector in the inertial frame [m] + * @param[in] velocity_i_m_s: Velocity vector in the inertial frame [m/s] + */ + void CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); }; #endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ From 0059ecba81a81ab65c7378e09f8a8af86a66e8a4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:01:23 +0100 Subject: [PATCH 0654/1086] Fix public function names --- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.cpp | 2 +- src/library/orbit/kepler_orbit.cpp | 2 +- src/library/orbit/kepler_orbit.hpp | 4 ++-- src/library/orbit/orbital_elements.cpp | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 9a9590440..1c83e62af 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -35,7 +35,7 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) } // Update reference orbit - reference_kepler_orbit.CalcPosVel(current_time_jd); + reference_kepler_orbit.CalcOrbit(current_time_jd); reference_position_i_m_ = reference_kepler_orbit.GetPosition_i_m(); reference_velocity_i_m_s_ = reference_kepler_orbit.GetVelocity_i_m_s(); diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 45ed76d63..6fbb5ae7f 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -132,7 +132,7 @@ libra::Vector<6> InitializePosVel(std::string initialize_file, double current_ti OrbitalElements oe(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); KeplerOrbit kepler_orbit(mu_m3_s2, oe); - kepler_orbit.CalcPosVel(current_time_jd); + kepler_orbit.CalcOrbit(current_time_jd); position_i_m = kepler_orbit.GetPosition_i_m(); velocity_i_m_s = kepler_orbit.GetVelocity_i_m_s(); } else if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 9ce051cd2..1137b7e1c 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -26,7 +26,7 @@ void KeplerOrbitPropagation::Propagate(double end_time_s, double current_time_jd // Private Function void KeplerOrbitPropagation::UpdateState(const double current_time_jd) { - CalcPosVel(current_time_jd); + CalcOrbit(current_time_jd); spacecraft_position_i_m_ = position_i_m_; spacecraft_velocity_i_m_s_ = velocity_i_m_s_; TransformEciToEcef(); diff --git a/src/library/orbit/kepler_orbit.cpp b/src/library/orbit/kepler_orbit.cpp index 59dcdadea..9816ff036 100644 --- a/src/library/orbit/kepler_orbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -27,7 +27,7 @@ void KeplerOrbit::CalcConstKeplerMotion() { dcm_inplane_to_i_ = dcm_raan * dcm_inc_arg; } -void KeplerOrbit::CalcPosVel(double time_jday) { +void KeplerOrbit::CalcOrbit(double time_jday) { // replace to short name variables double a_m = oe_.GetSemiMajorAxis_m(); double e = oe_.GetEccentricity(); diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 14817c354..3df7a80ac 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -35,11 +35,11 @@ class KeplerOrbit { ~KeplerOrbit(); /** - * @fn CalcPosVel + * @fn CalcOrbit * @brief Calculate position and velocity with Kepler orbit propagation * @param [in] time_jday: Time expressed as Julian day [day] */ - void CalcPosVel(double time_jday); + void CalcOrbit(double time_jday); /** * @fn GetPosition_i_m diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index 146a802b5..d49df014f 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -35,7 +35,7 @@ void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_ // common variables double r_m = norm(position_i_m); double v2_m2_s2 = inner_product(velocity_i_m_s, velocity_i_m_s); - libra::Vector<3> h; + libra::Vector<3> h; //!< angular momentum vector h = outer_product(position_i_m, velocity_i_m_s); double h_norm = norm(h); From 4e20e88adac3c8ffeea4acd485a8c2e2e256bf71 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:02:28 +0100 Subject: [PATCH 0655/1086] Fix enum name --- src/dynamics/orbit/initialize_orbit.cpp | 2 +- src/dynamics/orbit/relative_orbit.cpp | 6 +++--- src/dynamics/orbit/relative_orbit.hpp | 6 +++--- src/library/orbit/relative_orbit_models.hpp | 4 ++-- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 6fbb5ae7f..1168d5054 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -47,7 +47,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string RelativeOrbit::RelativeOrbitUpdateMethod update_method = (RelativeOrbit::RelativeOrbitUpdateMethod)(conf.ReadInt(section_, "relative_orbit_update_method")); RelativeOrbitModel relative_dynamics_model_type = (RelativeOrbitModel)(conf.ReadInt(section_, "relative_dynamics_model_type")); - STMModel stm_model_type = (STMModel)(conf.ReadInt(section_, "stm_model_type")); + StmModel stm_model_type = (StmModel)(conf.ReadInt(section_, "stm_model_type")); libra::Vector<3> init_relative_position_lvlh; conf.ReadVector<3>(section_, "initial_relative_position_lvlh_m", init_relative_position_lvlh); diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 73c19c145..5591bb375 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -10,7 +10,7 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, - RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, + RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, StmModel stm_model_type, RelativeInformation* relative_information) : Orbit(celestial_information), libra::ODE<6>(time_step_s), @@ -79,9 +79,9 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m } } -void RelativeOrbit::CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { +void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { switch (stm_model_type) { - case STMModel::HCW: { + case StmModel::HCW: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu_m3_s2, elapsed_sec); } diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 1f15aa4dd..3cc7b8af4 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -40,7 +40,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { */ RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, RelativeOrbitUpdateMethod update_method, - RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* relative_information); + RelativeOrbitModel relative_dynamics_model_type, StmModel stm_model_type, RelativeInformation* relative_information); /** * @fn ~RelativeOrbit * @brief Destructor @@ -81,7 +81,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { RelativeOrbitUpdateMethod update_method_; //!< Update method RelativeOrbitModel relative_dynamics_model_type_; //!< Relative dynamics model type - STMModel stm_model_type_; //!< State Transition Matrix model type + StmModel stm_model_type_; //!< State Transition Matrix model type RelativeInformation* relative_information_; //!< Relative information /** @@ -110,7 +110,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] elapsed_sec: Elapsed time [sec] */ - void CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); + void CalculateStm(StmModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); /** * @fn PropagateRk4 * @brief Propagate relative orbit with RK4 diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index 4db6cb79a..291c26446 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -16,10 +16,10 @@ enum class RelativeOrbitModel { Hill = 0 }; /** - * @enum STMModel + * @enum StmModel * @brief State Transition Matrix for the relative orbit */ -enum class STMModel { HCW = 0 }; +enum class StmModel { HCW = 0 }; // Dynamics Models /** From 6c558986ad2a4bbe21625f4cf7355b7b4cfa904f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:03:19 +0100 Subject: [PATCH 0656/1086] Fix public function name --- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/library/orbit/relative_orbit_models.cpp | 4 ++-- src/library/orbit/relative_orbit_models.hpp | 8 ++++---- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 5591bb375..60e038c43 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -70,7 +70,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, mu_m3_s2); + system_matrix_ = CalcHillSystemMatrix(reference_sat_orbit_radius, mu_m3_s2); } default: { // NOT REACHED @@ -83,7 +83,7 @@ void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference switch (stm_model_type) { case StmModel::HCW: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu_m3_s2, elapsed_sec); + stm_ = CalcHcwStm(reference_sat_orbit_radius, mu_m3_s2, elapsed_sec); } default: { // NOT REACHED diff --git a/src/library/orbit/relative_orbit_models.cpp b/src/library/orbit/relative_orbit_models.cpp index 07185cd0e..51f9e88be 100644 --- a/src/library/orbit/relative_orbit_models.cpp +++ b/src/library/orbit/relative_orbit_models.cpp @@ -4,7 +4,7 @@ */ #include "relative_orbit_models.hpp" -libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu) { +libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius, double mu) { libra::Matrix<6, 6> system_matrix; double n = sqrt(mu / pow(orbit_radius, 3)); @@ -48,7 +48,7 @@ libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu) { return system_matrix; } -libra::Matrix<6, 6> CalculateHCWSTM(double orbit_radius, double mu, double elapsed_sec) { +libra::Matrix<6, 6> CalcHcwStm(double orbit_radius, double mu, double elapsed_sec) { libra::Matrix<6, 6> stm; double n = sqrt(mu / pow(orbit_radius, 3)); diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index 291c26446..d780cf160 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -23,23 +23,23 @@ enum class StmModel { HCW = 0 }; // Dynamics Models /** - * @fn CalculateHillSystemMatrix + * @fn CalcHillSystemMatrix * @brief Calculate Hill System Matrix * @param [in] orbit_radius: Orbit radius [m] * @param [in] mu: Gravity constant of the center body [m3/s2] * @return System matrix */ -libra::Matrix<6, 6> CalculateHillSystemMatrix(double orbit_radius, double mu); +libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius, double mu); // STMs /** - * @fn CalculateHCWSTM + * @fn CalcHcwStm * @brief Calculate HCW State Transition Matrix * @param [in] orbit_radius: Orbit radius [m] * @param [in] mu: Gravity constant of the center body [m3/s2] * @param [in] mu: Elapsed time [s] * @return State Transition Matrix */ -libra::Matrix<6, 6> CalculateHCWSTM(double orbit_radius, double mu, double elapsed_sec); +libra::Matrix<6, 6> CalcHcwStm(double orbit_radius, double mu, double elapsed_sec); #endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ From 68fbb2ba2f3a844478b5cc972cf4feffb921301e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:05:08 +0100 Subject: [PATCH 0657/1086] Fix function argument name --- src/library/orbit/relative_orbit_models.cpp | 10 +++++----- src/library/orbit/relative_orbit_models.hpp | 14 +++++++------- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/library/orbit/relative_orbit_models.cpp b/src/library/orbit/relative_orbit_models.cpp index 51f9e88be..ae78641e5 100644 --- a/src/library/orbit/relative_orbit_models.cpp +++ b/src/library/orbit/relative_orbit_models.cpp @@ -4,10 +4,10 @@ */ #include "relative_orbit_models.hpp" -libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius, double mu) { +libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius_m, double mu_m3_s2) { libra::Matrix<6, 6> system_matrix; - double n = sqrt(mu / pow(orbit_radius, 3)); + double n = sqrt(mu_m3_s2 / pow(orbit_radius_m, 3)); system_matrix[0][0] = 0.0; system_matrix[0][1] = 0.0; system_matrix[0][2] = 0.0; @@ -48,11 +48,11 @@ libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius, double mu) { return system_matrix; } -libra::Matrix<6, 6> CalcHcwStm(double orbit_radius, double mu, double elapsed_sec) { +libra::Matrix<6, 6> CalcHcwStm(double orbit_radius_m, double mu_m3_s2, double elapsed_time_s) { libra::Matrix<6, 6> stm; - double n = sqrt(mu / pow(orbit_radius, 3)); - double t = elapsed_sec; + double n = sqrt(mu_m3_s2 / pow(orbit_radius_m, 3)); + double t = elapsed_time_s; stm[0][0] = 4.0 - 3.0 * cos(n * t); stm[0][1] = 0.0; stm[0][2] = 0.0; diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index d780cf160..71eb9ce23 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -25,21 +25,21 @@ enum class StmModel { HCW = 0 }; /** * @fn CalcHillSystemMatrix * @brief Calculate Hill System Matrix - * @param [in] orbit_radius: Orbit radius [m] - * @param [in] mu: Gravity constant of the center body [m3/s2] + * @param [in] orbit_radius_m: Orbit radius [m] + * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] * @return System matrix */ -libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius, double mu); +libra::Matrix<6, 6> CalcHillSystemMatrix(const double orbit_radius_m, const double mu_m3_s2); // STMs /** * @fn CalcHcwStm * @brief Calculate HCW State Transition Matrix - * @param [in] orbit_radius: Orbit radius [m] - * @param [in] mu: Gravity constant of the center body [m3/s2] - * @param [in] mu: Elapsed time [s] + * @param [in] orbit_radius_m: Orbit radius [m] + * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] elapsed_time_s: Elapsed time [s] * @return State Transition Matrix */ -libra::Matrix<6, 6> CalcHcwStm(double orbit_radius, double mu, double elapsed_sec); +libra::Matrix<6, 6> CalcHcwStm(const double orbit_radius_m, const double mu_m3_s2, const double elapsed_time_s); #endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ From 8f13cecf8b1c5ff4e6de541fa7eca2f8842def23 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:10:28 +0100 Subject: [PATCH 0658/1086] Fix private variables name --- src/library/external/inih/cpp/INIReader.cpp | 4 ++-- src/library/external/inih/cpp/INIReader.h | 2 +- src/library/utilities/ring_buffer.cpp | 25 +++++++++++---------- src/library/utilities/ring_buffer.hpp | 8 +++---- 4 files changed, 20 insertions(+), 19 deletions(-) diff --git a/src/library/external/inih/cpp/INIReader.cpp b/src/library/external/inih/cpp/INIReader.cpp index 87743d226..1e8099105 100644 --- a/src/library/external/inih/cpp/INIReader.cpp +++ b/src/library/external/inih/cpp/INIReader.cpp @@ -21,8 +21,8 @@ using std::string; INIReader::INIReader(const string& filename) { _error = ini_parse(filename.c_str(), ValueHandler, this); } -INIReader::INIReader(const char* buffer, size_t buffer_size) { - string content(buffer, buffer_size); +INIReader::INIReader(const char* buffer, size_t buffer_size_) { + string content(buffer, buffer_size_); _error = ini_parse_string(content.c_str(), ValueHandler, this); } diff --git a/src/library/external/inih/cpp/INIReader.h b/src/library/external/inih/cpp/INIReader.h index d4c23eb4f..da51ff62b 100644 --- a/src/library/external/inih/cpp/INIReader.h +++ b/src/library/external/inih/cpp/INIReader.h @@ -25,7 +25,7 @@ class INIReader { // Construct INIReader and parse given buffer. See ini.h for more info // about the parsing. - explicit INIReader(const char* buffer, size_t buffer_size); + explicit INIReader(const char* buffer, size_t buffer_size_); // Return the result of ini_parse(), i.e., 0 on success, line number of // first error on parse error, or -1 on file open error. diff --git a/src/library/utilities/ring_buffer.cpp b/src/library/utilities/ring_buffer.cpp index 764051729..bb19beb5b 100644 --- a/src/library/utilities/ring_buffer.cpp +++ b/src/library/utilities/ring_buffer.cpp @@ -10,20 +10,20 @@ #include #include -RingBuffer::RingBuffer(int bufSize) : kBufferSize(bufSize) { - buf_ = new byte[bufSize]; - wp_ = 0; - rp_ = 0; +RingBuffer::RingBuffer(int bufSize) : buffer_size_(bufSize) { + buffer_ = new byte[bufSize]; + write_pointer = 0; + read_pointer = 0; } -RingBuffer::~RingBuffer() { delete[] buf_; } +RingBuffer::~RingBuffer() { delete[] buffer_; } int RingBuffer::Write(byte* buffer, int offset, int count) { int write_count = 0; while (write_count != count) { - int write_len = std::min(kBufferSize - wp_, count - write_count); - memcpy(&buf_[wp_], &buffer[offset + write_count], write_len); - wp_ = (wp_ + write_len == kBufferSize) ? 0 : wp_ + write_len; + int write_len = std::min(buffer_size_ - write_pointer, count - write_count); + memcpy(&buffer_[write_pointer], &buffer[offset + write_count], write_len); + write_pointer = (write_pointer + write_len == buffer_size_) ? 0 : write_pointer + write_len; write_count += write_len; } @@ -34,10 +34,11 @@ int RingBuffer::Read(byte* buffer, int offset, int count) { int read_count = 0; // There are four behaviors depending on whether the RP overtakes the WP, or // whether all of the RP to the WP are requested by count. - while (read_count != count && wp_ != rp_) { - int read_len = (wp_ > rp_) ? std::min(wp_ - rp_, count - read_count) : std::min(kBufferSize - rp_, count - read_count); - memcpy(&buffer[offset + read_count], &buf_[rp_], read_len); - rp_ = (rp_ + read_len == kBufferSize) ? 0 : rp_ + read_len; + while (read_count != count && write_pointer != read_pointer) { + int read_len = (write_pointer > read_pointer) ? std::min(write_pointer - read_pointer, count - read_count) + : std::min(buffer_size_ - read_pointer, count - read_count); + memcpy(&buffer[offset + read_count], &buffer_[read_pointer], read_len); + read_pointer = (read_pointer + read_len == buffer_size_) ? 0 : read_pointer + read_len; read_count += read_len; } diff --git a/src/library/utilities/ring_buffer.hpp b/src/library/utilities/ring_buffer.hpp index d329e1ce1..33b7c046b 100644 --- a/src/library/utilities/ring_buffer.hpp +++ b/src/library/utilities/ring_buffer.hpp @@ -46,10 +46,10 @@ class RingBuffer { int Read(byte* buffer, int offset, int count); private: - const int kBufferSize; //!< Buffer size - byte* buf_; //!< Buffer - int rp_; //!< Read pointer - int wp_; //!< Write pointer + int buffer_size_; //!< Buffer size + byte* buffer_; //!< Buffer + int read_pointer; //!< Read pointer + int write_pointer; //!< Write pointer }; #endif // S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ From aa4a4848622efddca6f101b8642c0054e93bb3a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:12:58 +0100 Subject: [PATCH 0659/1086] Fix function argument names --- src/library/utilities/ring_buffer.cpp | 32 +++++++++++++-------------- src/library/utilities/ring_buffer.hpp | 24 ++++++++++---------- 2 files changed, 28 insertions(+), 28 deletions(-) diff --git a/src/library/utilities/ring_buffer.cpp b/src/library/utilities/ring_buffer.cpp index bb19beb5b..da6721477 100644 --- a/src/library/utilities/ring_buffer.cpp +++ b/src/library/utilities/ring_buffer.cpp @@ -10,35 +10,35 @@ #include #include -RingBuffer::RingBuffer(int bufSize) : buffer_size_(bufSize) { - buffer_ = new byte[bufSize]; - write_pointer = 0; - read_pointer = 0; +RingBuffer::RingBuffer(int buffer_size) : buffer_size_(buffer_size) { + buffer_ = new byte[buffer_size]; + write_pointer_ = 0; + read_pointer_ = 0; } RingBuffer::~RingBuffer() { delete[] buffer_; } -int RingBuffer::Write(byte* buffer, int offset, int count) { +int RingBuffer::Write(byte* buffer, int offset, int data_length) { int write_count = 0; - while (write_count != count) { - int write_len = std::min(buffer_size_ - write_pointer, count - write_count); - memcpy(&buffer_[write_pointer], &buffer[offset + write_count], write_len); - write_pointer = (write_pointer + write_len == buffer_size_) ? 0 : write_pointer + write_len; + while (write_count != data_length) { + int write_len = std::min(buffer_size_ - write_pointer_, data_length - write_count); + memcpy(&buffer_[write_pointer_], &buffer[offset + write_count], write_len); + write_pointer_ = (write_pointer_ + write_len == buffer_size_) ? 0 : write_pointer_ + write_len; write_count += write_len; } return write_count; } -int RingBuffer::Read(byte* buffer, int offset, int count) { +int RingBuffer::Read(byte* buffer, int offset, int data_length) { int read_count = 0; // There are four behaviors depending on whether the RP overtakes the WP, or - // whether all of the RP to the WP are requested by count. - while (read_count != count && write_pointer != read_pointer) { - int read_len = (write_pointer > read_pointer) ? std::min(write_pointer - read_pointer, count - read_count) - : std::min(buffer_size_ - read_pointer, count - read_count); - memcpy(&buffer[offset + read_count], &buffer_[read_pointer], read_len); - read_pointer = (read_pointer + read_len == buffer_size_) ? 0 : read_pointer + read_len; + // whether all of the RP to the WP are requested by data_length. + while (read_count != data_length && write_pointer_ != read_pointer_) { + int read_len = (write_pointer_ > read_pointer_) ? std::min(write_pointer_ - read_pointer_, data_length - read_count) + : std::min(buffer_size_ - read_pointer_, data_length - read_count); + memcpy(&buffer[offset + read_count], &buffer_[read_pointer_], read_len); + read_pointer_ = (read_pointer_ + read_len == buffer_size_) ? 0 : read_pointer_ + read_len; read_count += read_len; } diff --git a/src/library/utilities/ring_buffer.hpp b/src/library/utilities/ring_buffer.hpp index 33b7c046b..55d6fddce 100644 --- a/src/library/utilities/ring_buffer.hpp +++ b/src/library/utilities/ring_buffer.hpp @@ -17,9 +17,9 @@ class RingBuffer { /** * @fn RingBuffer * @brief Constructor - * @param [in] bufSize: Buffer size + * @param [in] buffer_size: Buffer size */ - RingBuffer(int bufSize); + RingBuffer(int buffer_size); /** * @fn ~RingBuffer * @brief Destructor @@ -28,28 +28,28 @@ class RingBuffer { /** * @fn Write - * @brief Write data of (buffer[offset] to buffer[offset + count]) to the ring buffer's write pointer + * @brief Write data of (buffer[offset] to buffer[offset + data_length]) to the ring buffer's write pointer * @param [in] buffer: Data * @param [in] offset: Data offset for buffer - * @param [in] count: Data length for buffer + * @param [in] data_length: Data length for buffer * @return Number of bytes written */ - int Write(byte* buffer, int offset, int count); + int Write(byte* buffer, int offset, int data_length); /** * @fn Read - * @brief Read data at the read pointer of the ring buffer and store the data to the buffer[offset] to buffer[offset + count] + * @brief Read data at the read pointer of the ring buffer and store the data to the buffer[offset] to buffer[offset + data_length] * @param [in] buffer: Data * @param [in] offset: Data offset for buffer - * @param [in] count: Data length for buffer + * @param [in] data_length: Data length for buffer * @return Number of bytes read */ - int Read(byte* buffer, int offset, int count); + int Read(byte* buffer, int offset, int data_length); private: - int buffer_size_; //!< Buffer size - byte* buffer_; //!< Buffer - int read_pointer; //!< Read pointer - int write_pointer; //!< Write pointer + int buffer_size_; //!< Buffer size + byte* buffer_; //!< Buffer + int read_pointer_; //!< Read pointer + int write_pointer_; //!< Write pointer }; #endif // S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ From ee2617089cc535b82954f5fe091a6f0871057ce1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 16:15:42 +0100 Subject: [PATCH 0660/1086] Fix public function name --- src/library/utilities/endian.h | 2 +- src/library/utilities/quantization.cpp | 6 +++--- src/library/utilities/quantization.hpp | 10 +++++----- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/library/utilities/endian.h b/src/library/utilities/endian.h index cee86b6cf..ce9ffff0f 100644 --- a/src/library/utilities/endian.h +++ b/src/library/utilities/endian.h @@ -20,4 +20,4 @@ */ void *endian_memcpy(void *dst, const void *src, size_t count); -#endif // S2E_LIBRARY_UTILITIES_ENDIAN_HPP_ \ No newline at end of file +#endif // S2E_LIBRARY_UTILITIES_ENDIAN_HPP_ diff --git a/src/library/utilities/quantization.cpp b/src/library/utilities/quantization.cpp index d75633ff6..114c0e2fe 100644 --- a/src/library/utilities/quantization.cpp +++ b/src/library/utilities/quantization.cpp @@ -5,9 +5,9 @@ #include "quantization.hpp" -double quantization(double continuous_num, double resolution) { - int bin_num = (int)((double)continuous_num / resolution); +double quantization(const double continuous_number, const double resolution) { + int bin_num = (int)((double)continuous_number / resolution); return (double)bin_num * resolution; } -float quantization_f(double continuous_num, double resolution) { return (float)quantization(continuous_num, resolution); } +float quantization_float(const double continuous_number, const double resolution) { return (float)quantization(continuous_number, resolution); } diff --git a/src/library/utilities/quantization.hpp b/src/library/utilities/quantization.hpp index d164375b3..f23eebdeb 100644 --- a/src/library/utilities/quantization.hpp +++ b/src/library/utilities/quantization.hpp @@ -9,19 +9,19 @@ /** * @fn quantization * @brief Default constructor without any initialization - * @param [in] continuous_num: Target number + * @param [in] continuous_number: Target number * @param [in] resolution: Resolution of the quantization * @return Quantized value (double) */ -double quantization(double continuous_num, double resolution); +double quantization(const double continuous_number, const double resolution); /** - * @fn quantization_f + * @fn quantization_float * @brief Default constructor without any initialization - * @param [in] continuous_num: Target number + * @param [in] continuous_number: Target number * @param [in] resolution: Resolution of the quantization * @return Quantized value (float) */ -float quantization_f(double continuous_num, double resolution); +float quantization_float(const double continuous_number, const double resolution); #endif // S2E_LIBRARY_UTILITIES_QUANTIZATION_HPP_ From 6990c8a432e424103a7743843c35566f7b5e4c01 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 20:51:35 +0100 Subject: [PATCH 0661/1086] Fix global randomization class name and variable names --- .../base/sensor_template_functions.hpp | 2 +- src/components/real/aocs/gnss_receiver.cpp | 12 ++++++------ src/components/real/aocs/magnetorquer.cpp | 4 ++-- src/components/real/aocs/star_sensor.cpp | 12 ++++++------ src/components/real/aocs/sun_sensor.cpp | 6 +++--- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- .../randomization/global_randomization.cpp | 16 ++++++++-------- .../randomization/global_randomization.hpp | 12 ++++++------ .../random_walk_template_functions.hpp | 2 +- 11 files changed, 36 insertions(+), 36 deletions(-) diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index ce02ba2f4..11825c127 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -18,7 +18,7 @@ SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra:: bias_c_(bias_c), n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c) { for (size_t i = 0; i < N; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i], g_rand.MakeSeed()); + nrs_c_[i].set_param(0.0, nr_stddev_c[i], global_randomization.MakeSeed()); } RangeCheck(); } diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 215df98a8..597ad5940 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -17,9 +17,9 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const ch_max_(ch_max), antenna_position_b_(ant_pos_b), q_b2c_(q_b2c), - nrs_eci_x_(0.0, noise_std[0], g_rand.MakeSeed()), - nrs_eci_y_(0.0, noise_std[1], g_rand.MakeSeed()), - nrs_eci_z_(0.0, noise_std[2], g_rand.MakeSeed()), + nrs_eci_x_(0.0, noise_std[0], global_randomization.MakeSeed()), + nrs_eci_y_(0.0, noise_std[1], global_randomization.MakeSeed()), + nrs_eci_z_(0.0, noise_std[2], global_randomization.MakeSeed()), half_width_(half_width), gnss_id_(gnss_id), antenna_model_(antenna_model), @@ -35,9 +35,9 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, Power ch_max_(ch_max), antenna_position_b_(ant_pos_b), q_b2c_(q_b2c), - nrs_eci_x_(0.0, noise_std[0], g_rand.MakeSeed()), - nrs_eci_y_(0.0, noise_std[1], g_rand.MakeSeed()), - nrs_eci_z_(0.0, noise_std[2], g_rand.MakeSeed()), + nrs_eci_x_(0.0, noise_std[0], global_randomization.MakeSeed()), + nrs_eci_y_(0.0, noise_std[1], global_randomization.MakeSeed()), + nrs_eci_z_(0.0, noise_std[2], global_randomization.MakeSeed()), half_width_(half_width), gnss_id_(gnss_id), antenna_model_(antenna_model), diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 182304afc..015145a34 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -25,7 +25,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), mag_env_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // g_rand.MakeSeed() + nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } @@ -44,7 +44,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), mag_env_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // g_rand.MakeSeed() + nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 969526144..7621f50fb 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -22,9 +22,9 @@ STT::STT(const int prescaler, ClockGenerator* clock_gen, const int id, const lib : ComponentBase(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), - rot_(g_rand.MakeSeed()), - n_ortho_(0.0, sigma_ortho, g_rand.MakeSeed()), - n_sight_(0.0, sigma_sight, g_rand.MakeSeed()), + rot_(global_randomization.MakeSeed()), + n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), + n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), pos_(0), step_time_(step_time), output_delay_(output_delay), @@ -45,9 +45,9 @@ STT::STT(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, : ComponentBase(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), - rot_(g_rand.MakeSeed()), - n_ortho_(0.0, sigma_ortho, g_rand.MakeSeed()), - n_sight_(0.0, sigma_sight, g_rand.MakeSeed()), + rot_(global_randomization.MakeSeed()), + n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), + n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), pos_(0), step_time_(step_time), output_delay_(output_delay), diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 45f340b45..b605af4c0 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -42,13 +42,13 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* void SunSensor::Initialize(const double nr_stddev_c, const double nr_bias_stddev_c) { // Bias - NormalRand nr(0.0, nr_bias_stddev_c, g_rand.MakeSeed()); + NormalRand nr(0.0, nr_bias_stddev_c, global_randomization.MakeSeed()); bias_alpha_ += nr; bias_beta_ += nr; // Normal Random - nrs_alpha_.set_param(0.0, nr_stddev_c); // g_rand.MakeSeed() - nrs_beta_.set_param(0.0, nr_stddev_c); // g_rand.MakeSeed() + nrs_alpha_.set_param(0.0, nr_stddev_c); // global_randomization.MakeSeed() + nrs_beta_.set_param(0.0, nr_stddev_c); // global_randomization.MakeSeed() } void SunSensor::MainRoutine(int count) { UNUSED(count); diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 485b59f4a..2a547f580 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -33,7 +33,7 @@ void MagneticDisturbance::CalcRMM() { static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRMMRWDev()); static libra::Vector<3> random_walk_limit(rmm_params_.GetRMMRWLimit()); 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, rmm_params_.GetRMMWNVar(), g_rand.MakeSeed()); + static libra::NormalRand normal_random(0.0, rmm_params_.GetRMMWNVar(), global_randomization.MakeSeed()); rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); for (int i = 0; i < 3; ++i) { diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 62c809082..0552fd4a2 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -201,7 +201,7 @@ double Atmosphere::CalcStandard(const double altitude_m) { 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_, g_rand.MakeSeed()); + libra::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 5894d0770..e6a6ce75f 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 libra::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_, g_rand.MakeSeed()); + static libra::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/library/randomization/global_randomization.cpp b/src/library/randomization/global_randomization.cpp index 30fe34d32..0c281ebf7 100644 --- a/src/library/randomization/global_randomization.cpp +++ b/src/library/randomization/global_randomization.cpp @@ -5,18 +5,18 @@ #include "global_randomization.hpp" -GlobalRand g_rand; +GlobalRandomization global_randomization; -GlobalRand::GlobalRand() { seed_ = 0xdeadbeef; } +GlobalRandomization::GlobalRandomization() { seed_ = 0xdeadbeef; } -void GlobalRand::SetSeed(long seed) { - base_rand_.init(seed); - // double dl = base_rand_; +void GlobalRandomization::SetSeed(long seed) { + base_randomizer_.init(seed); + // double dl = base_randomizer_; } -long GlobalRand::MakeSeed() { - double rand = base_rand_; - long seed = (long)((rand - 0.5) * MAX_SEED); +long GlobalRandomization::MakeSeed() { + double rand = base_randomizer_; + long seed = (long)((rand - 0.5) * kMaxSeed); if (seed == 0) { seed = 0xdeadbeef; } diff --git a/src/library/randomization/global_randomization.hpp b/src/library/randomization/global_randomization.hpp index 85f876cc7..047775bab 100644 --- a/src/library/randomization/global_randomization.hpp +++ b/src/library/randomization/global_randomization.hpp @@ -13,13 +13,13 @@ * @brief Class to manage global randomization * @note Used to make randomized seed for other randomization */ -class GlobalRand { +class GlobalRandomization { public: /** - * @fn GlobalRand + * @fn GlobalRandomization * @brief Constructor */ - GlobalRand(); + GlobalRandomization(); /** * @fn SetSeed * @brief Set randomized seed value @@ -32,11 +32,11 @@ class GlobalRand { long MakeSeed(); private: - static const unsigned int MAX_SEED = 0xffffffff; //!< Maximum value of seed - libra::Ran0 base_rand_; //!< Base of global randomization + static const unsigned int kMaxSeed = 0xffffffff; //!< Maximum value of seed + libra::Ran0 base_randomizer_; //!< Base of global randomization long seed_; //!< Seed of global randomization }; -extern GlobalRand g_rand; //!< Global randomization +extern GlobalRandomization global_randomization; //!< Global randomization #endif // S2E_LIBRARY_RANDOMIZATION_GLOBAL_RANDOMIZATION_HPP_ diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 15c761d14..5342c4830 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -14,7 +14,7 @@ RandomWalk::RandomWalk(double step_width, const libra::Vector& stddev, con : libra::ODE(step_width), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { - nrs_[i].set_param(0.0, stddev[i], g_rand.MakeSeed()); + nrs_[i].set_param(0.0, stddev[i], global_randomization.MakeSeed()); } } From 43a88cab2e6b965f8ded935e1d9f0e754d05ae2f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 20:59:40 +0100 Subject: [PATCH 0662/1086] Fix member variables name --- ...standard_linear_congruential_generator.cpp | 10 ++++---- ...standard_linear_congruential_generator.hpp | 16 ++++++------- ...ar_congruential_generator_with_shuffle.cpp | 24 +++++++++---------- ...ar_congruential_generator_with_shuffle.hpp | 16 ++++++------- 4 files changed, 33 insertions(+), 33 deletions(-) diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp index 96f31b63c..72fe07741 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp @@ -9,7 +9,7 @@ using libra::Ran0; #include -const double Ran0::AM_ = 1.0 / Ran0::M; +const double Ran0::a_m_ = 1.0 / Ran0::m_; Ran0::Ran0() : seed_(0xdeadbeef) {} @@ -26,10 +26,10 @@ void Ran0::init(long seed) { } Ran0::operator double() { - long k = seed_ / Q_; - seed_ = A * (seed_ - k * Q_) - R_ * k; + long k = seed_ / q_; + seed_ = a_ * (seed_ - k * q_) - r_ * k; if (seed_ < 0) { - seed_ += M; + seed_ += m_; } - return AM_ * seed_; + return a_m_ * seed_; } diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index 26ff8be54..f4b23a350 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -4,8 +4,8 @@ * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ -#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ namespace libra { @@ -15,8 +15,8 @@ namespace libra { */ class Ran0 { public: - static const long A = 16807; //!< Coefficient a for multiplication - static const long M = 2147483647; //!< Divisor for modulo + static const long a_ = 16807; //!< Coefficient a for multiplication + static const long m_ = 2147483647; //!< Divisor for modulo /** * @fn Ran0 @@ -45,13 +45,13 @@ class Ran0 { operator double(); private: - static const double AM_; //!< A/M - static const long Q_ = 127773; //!< Integer part of A/M - static const long R_ = 2836; //!< m mod a + static const double a_m_; //!< A/M + static const long q_ = 127773; //!< Integer part of A/M + static const long r_ = 2836; //!< m mod a long seed_; //!< Seed of randomization }; } // namespace libra -#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index 7d97cbcba..b9a7f2bcb 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -7,33 +7,33 @@ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" using libra::Ran1; -Ran1::Ran1() : y_(0) { init_(); } +Ran1::Ran1() : table_position_(0) { init_(); } -Ran1::Ran1(long seed) : ran0_(seed), y_(0) { init_(); } +Ran1::Ran1(long seed) : minimal_lcg_(seed), table_position_(0) { init_(); } void Ran1::init_seed(long seed) { - ran0_.init(seed); + minimal_lcg_.init(seed); init_(); } void Ran1::init_() { - // Warmup of ran0_ + // Warmup of minimal_lcg_ for (int i = 0; i < 8; i++) { - double temp = ran0_; + double temp = minimal_lcg_; static_cast(temp); } // Fill mixing table - for (size_t i = 0; i < V_SIZE_; i++) { - vec_[i] = ran0_; + for (size_t i = 0; i < kTableSize; i++) { + mixing_table_[i] = minimal_lcg_; } - // for(size_t i=0; i // size_t @@ -52,13 +52,13 @@ class Ran1 { */ void init_(); - Ran0 ran0_; //!< Randomization with Park and Miller's multiplicative congruential method - static const std::size_t V_SIZE_ = 32; //!< Number of elements for mixing table - double v_[V_SIZE_]; //!< Mixing table (Not used now) - std::size_t y_; //!< Position of mixing table - double vec_[V_SIZE_]; //!< Mixing table + Ran0 minimal_lcg_; //!< Randomization with Park and Miller's multiplicative congruential method + static const std::size_t kTableSize = 32; //!< Number of elements for mixing table + double v_[kTableSize]; //!< Mixing table (Not used now) + std::size_t table_position_; //!< Position of mixing table + double mixing_table_[kTableSize]; //!< Mixing table }; } // namespace libra -#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_WITH_SHUFFLE_HPP_ From af4dc42abedac4846bfdeb984680a379a7fdbdfa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:02:09 +0100 Subject: [PATCH 0663/1086] Fix public member variables name --- .../minimal_standard_linear_congruential_generator.cpp | 6 +++--- .../minimal_standard_linear_congruential_generator.hpp | 4 ++-- ..._standard_linear_congruential_generator_with_shuffle.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp index 72fe07741..e639e2e24 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp @@ -9,7 +9,7 @@ using libra::Ran0; #include -const double Ran0::a_m_ = 1.0 / Ran0::m_; +const double Ran0::a_m_ = 1.0 / Ran0::kM; Ran0::Ran0() : seed_(0xdeadbeef) {} @@ -27,9 +27,9 @@ void Ran0::init(long seed) { Ran0::operator double() { long k = seed_ / q_; - seed_ = a_ * (seed_ - k * q_) - r_ * k; + seed_ = kA * (seed_ - k * q_) - r_ * k; if (seed_ < 0) { - seed_ += m_; + seed_ += kM; } return a_m_ * seed_; } diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index f4b23a350..2b41fa1c4 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -15,8 +15,8 @@ namespace libra { */ class Ran0 { public: - static const long a_ = 16807; //!< Coefficient a for multiplication - static const long m_ = 2147483647; //!< Divisor for modulo + static const long kA = 16807; //!< Coefficient a for multiplication + static const long kM = 2147483647; //!< Divisor for modulo /** * @fn Ran0 diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index b9a7f2bcb..3f918ca8c 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -32,7 +32,7 @@ void Ran1::init_() { Ran1::operator double() { double out = mixing_table_[table_position_]; mixing_table_[table_position_] = minimal_lcg_; // Compensate next random value - table_position_ = (size_t)out * Ran0::m_; + table_position_ = (size_t)out * Ran0::kM; table_position_ %= kTableSize; // y <- [0 : kTableSize-1] return out; From 4ea6cc901b7001dbfd06a0ba1c1a4b2c9415a440 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:02:52 +0100 Subject: [PATCH 0664/1086] Remove unused private variables --- ...nimal_standard_linear_congruential_generator_with_shuffle.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index 11281cf6a..8762e6f80 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -54,7 +54,6 @@ class Ran1 { Ran0 minimal_lcg_; //!< Randomization with Park and Miller's multiplicative congruential method static const std::size_t kTableSize = 32; //!< Number of elements for mixing table - double v_[kTableSize]; //!< Mixing table (Not used now) std::size_t table_position_; //!< Position of mixing table double mixing_table_[kTableSize]; //!< Mixing table }; From 36d3b462796c7fdc165f54e5e6d5cc41b4e840a8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:06:17 +0100 Subject: [PATCH 0665/1086] Rename function name --- src/library/randomization/global_randomization.cpp | 4 ++-- src/library/randomization/global_randomization.hpp | 2 +- ...nimal_standard_linear_congruential_generator.cpp | 4 ++-- ...nimal_standard_linear_congruential_generator.hpp | 6 +++--- ...d_linear_congruential_generator_with_shuffle.cpp | 13 ++++++------- ...d_linear_congruential_generator_with_shuffle.hpp | 10 +++++----- .../normal_randomization_inline_functions.hpp | 2 +- 7 files changed, 20 insertions(+), 21 deletions(-) diff --git a/src/library/randomization/global_randomization.cpp b/src/library/randomization/global_randomization.cpp index 0c281ebf7..7a7282902 100644 --- a/src/library/randomization/global_randomization.cpp +++ b/src/library/randomization/global_randomization.cpp @@ -9,8 +9,8 @@ GlobalRandomization global_randomization; GlobalRandomization::GlobalRandomization() { seed_ = 0xdeadbeef; } -void GlobalRandomization::SetSeed(long seed) { - base_randomizer_.init(seed); +void GlobalRandomization::SetSeed(const long seed) { + base_randomizer_.Initialize(seed); // double dl = base_randomizer_; } diff --git a/src/library/randomization/global_randomization.hpp b/src/library/randomization/global_randomization.hpp index 047775bab..6827580e7 100644 --- a/src/library/randomization/global_randomization.hpp +++ b/src/library/randomization/global_randomization.hpp @@ -24,7 +24,7 @@ class GlobalRandomization { * @fn SetSeed * @brief Set randomized seed value */ - void SetSeed(long seed); + void SetSeed(const long seed); /** * @fn MakeSeed * @brief Set randomized seed value diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp index e639e2e24..734d050d8 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp @@ -13,12 +13,12 @@ const double Ran0::a_m_ = 1.0 / Ran0::kM; Ran0::Ran0() : seed_(0xdeadbeef) {} -Ran0::Ran0(long seed) : seed_(seed) { +Ran0::Ran0(const long seed) : seed_(seed) { if (seed == 0) { throw std::invalid_argument("Ran0:: seed is 0."); } } -void Ran0::init(long seed) { +void Ran0::Initialize(const long seed) { if (seed == 0) { throw std::invalid_argument("Ran0:: seed is 0."); } diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index 2b41fa1c4..ef1e5b7b9 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -28,14 +28,14 @@ class Ran0 { * @brief Default constructor with seed value * @param [in] seed: Seed of randomization */ - explicit Ran0(long seed); + explicit Ran0(const long seed); /** - * @fn init + * @fn Initialize * @brief Set seed value * @param [in] seed: Seed of randomization */ - void init(long seed); + void Initialize(const long seed); /** * @fn Cast operator of double type diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index 3f918ca8c..a436d7f12 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -7,16 +7,16 @@ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" using libra::Ran1; -Ran1::Ran1() : table_position_(0) { init_(); } +Ran1::Ran1() : table_position_(0) { Initialize(); } -Ran1::Ran1(long seed) : minimal_lcg_(seed), table_position_(0) { init_(); } +Ran1::Ran1(const long seed) : minimal_lcg_(seed), table_position_(0) { Initialize(); } -void Ran1::init_seed(long seed) { - minimal_lcg_.init(seed); - init_(); +void Ran1::InitSeed(const long seed) { + minimal_lcg_.Initialize(seed); + Initialize(); } -void Ran1::init_() { +void Ran1::Initialize() { // Warmup of minimal_lcg_ for (int i = 0; i < 8; i++) { double temp = minimal_lcg_; @@ -26,7 +26,6 @@ void Ran1::init_() { for (size_t i = 0; i < kTableSize; i++) { mixing_table_[i] = minimal_lcg_; } - // for(size_t i=0; i Date: Fri, 24 Feb 2023 21:09:29 +0100 Subject: [PATCH 0666/1086] Rename LCG class name --- src/components/real/aocs/star_sensor.hpp | 6 +++--- .../randomization/global_randomization.hpp | 2 +- ...al_standard_linear_congruential_generator.cpp | 16 ++++++++-------- ...al_standard_linear_congruential_generator.hpp | 12 ++++++------ ...inear_congruential_generator_with_shuffle.cpp | 14 +++++++------- ...inear_congruential_generator_with_shuffle.hpp | 14 +++++++------- .../randomization/normal_randomization.hpp | 16 ++++++++-------- 7 files changed, 40 insertions(+), 40 deletions(-) diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 13fb155fb..73e280601 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -112,9 +112,9 @@ class STT : public ComponentBase, public ILoggable { libra::Vector<3> ortho2_; //!< The second orthogonal direction of sight at component frame // Noise parameters - libra::Ran1 rot_; //!< Randomize object for orthogonal direction - libra::NormalRand n_ortho_; //!< Random noise for orthogonal direction of sight [rad] - libra::NormalRand n_sight_; //!< Random noise for sight direction [rad] + libra::MinimalStandardLcgWithShuffle rot_; //!< Randomize object for orthogonal direction + libra::NormalRand n_ortho_; //!< Random noise for orthogonal direction of sight [rad] + libra::NormalRand n_sight_; //!< Random noise for sight direction [rad] // Delay emulation parameters int MAX_DELAY; //!< Max delay diff --git a/src/library/randomization/global_randomization.hpp b/src/library/randomization/global_randomization.hpp index 6827580e7..f63b63e82 100644 --- a/src/library/randomization/global_randomization.hpp +++ b/src/library/randomization/global_randomization.hpp @@ -33,7 +33,7 @@ class GlobalRandomization { private: static const unsigned int kMaxSeed = 0xffffffff; //!< Maximum value of seed - libra::Ran0 base_randomizer_; //!< Base of global randomization + libra::MinimalStandardLcg base_randomizer_; //!< Base of global randomization long seed_; //!< Seed of global randomization }; diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp index 734d050d8..395a8943e 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.cpp @@ -5,27 +5,27 @@ */ #include "minimal_standard_linear_congruential_generator.hpp" -using libra::Ran0; +using libra::MinimalStandardLcg; #include -const double Ran0::a_m_ = 1.0 / Ran0::kM; +const double MinimalStandardLcg::a_m_ = 1.0 / MinimalStandardLcg::kM; -Ran0::Ran0() : seed_(0xdeadbeef) {} +MinimalStandardLcg::MinimalStandardLcg() : seed_(0xdeadbeef) {} -Ran0::Ran0(const long seed) : seed_(seed) { +MinimalStandardLcg::MinimalStandardLcg(const long seed) : seed_(seed) { if (seed == 0) { - throw std::invalid_argument("Ran0:: seed is 0."); + throw std::invalid_argument("MinimalStandardLcg:: seed is 0."); } } -void Ran0::Initialize(const long seed) { +void MinimalStandardLcg::Initialize(const long seed) { if (seed == 0) { - throw std::invalid_argument("Ran0:: seed is 0."); + throw std::invalid_argument("MinimalStandardLcg:: seed is 0."); } seed_ = seed; } -Ran0::operator double() { +MinimalStandardLcg::operator double() { long k = seed_ / q_; seed_ = kA * (seed_ - k * q_) - r_ * k; if (seed_ < 0) { diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index ef1e5b7b9..d2277fd4d 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -10,25 +10,25 @@ namespace libra { /** - * @class Ran0 + * @class MinimalStandardLcg * @brief Randomization with Park and Miller's multiplicative congruential and mixed method */ -class Ran0 { +class MinimalStandardLcg { public: static const long kA = 16807; //!< Coefficient a for multiplication static const long kM = 2147483647; //!< Divisor for modulo /** - * @fn Ran0 + * @fn MinimalStandardLcg * @brief Default constructor with default seed value */ - Ran0(); + MinimalStandardLcg(); /** - * @fn Ran0 + * @fn MinimalStandardLcg * @brief Default constructor with seed value * @param [in] seed: Seed of randomization */ - explicit Ran0(const long seed); + explicit MinimalStandardLcg(const long seed); /** * @fn Initialize diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index a436d7f12..95fbc7075 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -5,18 +5,18 @@ */ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" -using libra::Ran1; +using libra::MinimalStandardLcgWithShuffle; -Ran1::Ran1() : table_position_(0) { Initialize(); } +MinimalStandardLcgWithShuffle::MinimalStandardLcgWithShuffle() : table_position_(0) { Initialize(); } -Ran1::Ran1(const long seed) : minimal_lcg_(seed), table_position_(0) { Initialize(); } +MinimalStandardLcgWithShuffle::MinimalStandardLcgWithShuffle(const long seed) : minimal_lcg_(seed), table_position_(0) { Initialize(); } -void Ran1::InitSeed(const long seed) { +void MinimalStandardLcgWithShuffle::InitSeed(const long seed) { minimal_lcg_.Initialize(seed); Initialize(); } -void Ran1::Initialize() { +void MinimalStandardLcgWithShuffle::Initialize() { // Warmup of minimal_lcg_ for (int i = 0; i < 8; i++) { double temp = minimal_lcg_; @@ -28,10 +28,10 @@ void Ran1::Initialize() { } } -Ran1::operator double() { +MinimalStandardLcgWithShuffle::operator double() { double out = mixing_table_[table_position_]; mixing_table_[table_position_] = minimal_lcg_; // Compensate next random value - table_position_ = (size_t)out * Ran0::kM; + table_position_ = (size_t)out * MinimalStandardLcg::kM; table_position_ %= kTableSize; // y <- [0 : kTableSize-1] return out; diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index 75adb4ac0..e7359e1d1 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -14,22 +14,22 @@ namespace libra { /** - * @class Ran1 + * @class MinimalStandardLcgWithShuffle * @brief Randomization with Park and Miller's multiplicative congruential method combined with mixed method */ -class Ran1 { +class MinimalStandardLcgWithShuffle { public: /** - * @fn Ran1 + * @fn MinimalStandardLcgWithShuffle * @brief Default constructor with default seed value */ - Ran1(); + MinimalStandardLcgWithShuffle(); /** - * @fn Ran1 + * @fn MinimalStandardLcgWithShuffle * @brief Default constructor with seed value * @param [in] seed: Seed of randomization */ - explicit Ran1(const long seed); + explicit MinimalStandardLcgWithShuffle(const long seed); /** * @fn Cast operator of double type @@ -52,7 +52,7 @@ class Ran1 { */ void Initialize(); - Ran0 minimal_lcg_; //!< Randomization with Park and Miller's multiplicative congruential method + MinimalStandardLcg minimal_lcg_; //!< Randomization with Park and Miller's multiplicative congruential method static const std::size_t kTableSize = 32; //!< Number of elements for mixing table std::size_t table_position_; //!< Position of mixing table double mixing_table_[kTableSize]; //!< Mixing table diff --git a/src/library/randomization/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp index 4b65d2e09..f97222d54 100644 --- a/src/library/randomization/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -8,7 +8,7 @@ #define S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" -using libra::Ran1; +using libra::MinimalStandardLcgWithShuffle; namespace libra { @@ -90,13 +90,13 @@ class NormalRand { inline void set_param(double avg, double stddev, long seed); private: - double avg_; //!< Average - double stddev_; //!< Standard deviation - Ran1 rand_; //!< Randomized origin to use Box-Muller method - double holder_; //!< Second random value. Box-Muller method generates two value at once. - //!< The second value is stored and used in the next call. - //!< It means that Box-Muller method is executed once per two call - bool is_empty_; //!< Flag to show the holder_ has available value + double avg_; //!< Average + double stddev_; //!< Standard deviation + MinimalStandardLcgWithShuffle rand_; //!< Randomized origin to use Box-Muller method + double holder_; //!< Second random value. Box-Muller method generates two value at once. + //!< The second value is stored and used in the next call. + //!< It means that Box-Muller method is executed once per two call + bool is_empty_; //!< Flag to show the holder_ has available value }; } // namespace libra From ad9f61b9664764f27f42f4399c5cd87477fd35d0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:10:00 +0100 Subject: [PATCH 0667/1086] Fix include guard --- .../minimal_standard_linear_congruential_generator.hpp | 6 +++--- ..._standard_linear_congruential_generator_with_shuffle.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp index d2277fd4d..70b97a695 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator.hpp @@ -4,8 +4,8 @@ * @note ran0 function in "NUMERICAL RECIPES in C, p.206" */ -#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ -#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ namespace libra { @@ -54,4 +54,4 @@ class MinimalStandardLcg { } // namespace libra -#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ diff --git a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index e7359e1d1..6c42dddba 100644 --- a/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp +++ b/src/library/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -4,8 +4,8 @@ * @note ran1 function in "NUMERICAL RECIPES in C, p.207-208" */ -#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_WITH_SHUFFLE_HPP_ -#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_WITH_SHUFFLE_HPP_ +#ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ +#define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ #include // size_t @@ -60,4 +60,4 @@ class MinimalStandardLcgWithShuffle { } // namespace libra -#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAr_CONGRUENTIAL_GENERATOr_WITH_SHUFFLE_HPP_ +#endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ From 44954cb80786bf42a1f6b7ec4145eb7dd97c1c0c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:13:03 +0100 Subject: [PATCH 0668/1086] Fix private variables --- .../randomization/normal_randomization.cpp | 15 ++++++++------- .../randomization/normal_randomization.hpp | 14 +++++++------- .../normal_randomization_inline_functions.hpp | 18 +++++++++--------- 3 files changed, 24 insertions(+), 23 deletions(-) diff --git a/src/library/randomization/normal_randomization.cpp b/src/library/randomization/normal_randomization.cpp index 0cc15aa61..ac9785c6c 100644 --- a/src/library/randomization/normal_randomization.cpp +++ b/src/library/randomization/normal_randomization.cpp @@ -9,18 +9,19 @@ using libra::NormalRand; #include //DBL_EPSILON #include //sqrt, log; -NormalRand::NormalRand() : avg_(0.0), stddev_(1.0), holder_(0.0), is_empty_(true) {} +NormalRand::NormalRand() : average_(0.0), standard_deviation_(1.0), holder_(0.0), is_empty_(true) {} -NormalRand::NormalRand(double avg, double stddev) : avg_(avg), stddev_(stddev), holder_(0.0), is_empty_(true) {} +NormalRand::NormalRand(double avg, double stddev) : average_(avg), standard_deviation_(stddev), holder_(0.0), is_empty_(true) {} -NormalRand::NormalRand(double avg, double stddev, long seed) throw() : avg_(avg), stddev_(stddev), rand_(seed), holder_(0.0), is_empty_(true) {} +NormalRand::NormalRand(double avg, double stddev, long seed) throw() + : average_(avg), standard_deviation_(stddev), randomizer_(seed), holder_(0.0), is_empty_(true) {} NormalRand::operator double() { if (is_empty_) { double v1, v2, rsq; do { - v1 = 2.0 * double(rand_) - 1.0; - v2 = 2.0 * rand_ - 1.0; + v1 = 2.0 * double(randomizer_) - 1.0; + v2 = 2.0 * randomizer_ - 1.0; rsq = v1 * v1 + v2 * v2; } while (rsq >= 1.0 || rsq < DBL_EPSILON); double fac = std::sqrt(-2.0 * std::log(rsq) / rsq); @@ -28,9 +29,9 @@ NormalRand::operator double() { holder_ = v1 * fac; is_empty_ = false; - return v2 * fac * stddev_ + avg_; + return v2 * fac * standard_deviation_ + average_; } else { is_empty_ = true; - return holder_ * stddev_ + avg_; + return holder_ * standard_deviation_ + average_; } } diff --git a/src/library/randomization/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp index f97222d54..4d9a4f393 100644 --- a/src/library/randomization/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -90,13 +90,13 @@ class NormalRand { inline void set_param(double avg, double stddev, long seed); private: - double avg_; //!< Average - double stddev_; //!< Standard deviation - MinimalStandardLcgWithShuffle rand_; //!< Randomized origin to use Box-Muller method - double holder_; //!< Second random value. Box-Muller method generates two value at once. - //!< The second value is stored and used in the next call. - //!< It means that Box-Muller method is executed once per two call - bool is_empty_; //!< Flag to show the holder_ has available value + double average_; //!< Average + double standard_deviation_; //!< Standard deviation + MinimalStandardLcgWithShuffle randomizer_; //!< Randomized origin to use Box-Muller method + double holder_; //!< Second random value. Box-Muller method generates two value at once. + //!< The second value is stored and used in the next call. + //!< It means that Box-Muller method is executed once per two call + bool is_empty_; //!< Flag to show the holder_ has available value }; } // namespace libra diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp index 2f3379332..2db2f6206 100644 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ b/src/library/randomization/normal_randomization_inline_functions.hpp @@ -8,23 +8,23 @@ namespace libra { -double NormalRand::avg() const { return avg_; } +double NormalRand::avg() const { return average_; } -void NormalRand::avg(double avg) { avg_ = avg; } +void NormalRand::avg(double avg) { average_ = avg; } -double NormalRand::stddev() const { return stddev_; } +double NormalRand::stddev() const { return standard_deviation_; } -void NormalRand::stddev(double stddev) { stddev_ = stddev; } +void NormalRand::stddev(double stddev) { standard_deviation_ = stddev; } void NormalRand::set_param(double avg, double stddev) { - avg_ = avg; - stddev_ = stddev; + average_ = avg; + standard_deviation_ = stddev; } void NormalRand::set_param(double avg, double stddev, long seed) { - avg_ = avg; - stddev_ = stddev; - rand_.InitSeed(seed); + average_ = avg; + standard_deviation_ = stddev; + randomizer_.InitSeed(seed); } } // namespace libra From d17a6242cc255c9f5c5a61c750e4b7a4b07a021f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:16:30 +0100 Subject: [PATCH 0669/1086] Fix function argument --- .../randomization/normal_randomization.cpp | 7 ++-- .../randomization/normal_randomization.hpp | 40 +++++++++---------- .../normal_randomization_inline_functions.hpp | 20 +++++----- src/library/randomization/random_walk.hpp | 4 +- .../random_walk_template_functions.hpp | 4 +- 5 files changed, 38 insertions(+), 37 deletions(-) diff --git a/src/library/randomization/normal_randomization.cpp b/src/library/randomization/normal_randomization.cpp index ac9785c6c..02eb484b7 100644 --- a/src/library/randomization/normal_randomization.cpp +++ b/src/library/randomization/normal_randomization.cpp @@ -11,10 +11,11 @@ using libra::NormalRand; NormalRand::NormalRand() : average_(0.0), standard_deviation_(1.0), holder_(0.0), is_empty_(true) {} -NormalRand::NormalRand(double avg, double stddev) : average_(avg), standard_deviation_(stddev), holder_(0.0), is_empty_(true) {} +NormalRand::NormalRand(double average, double standard_deviation) + : average_(average), standard_deviation_(standard_deviation), holder_(0.0), is_empty_(true) {} -NormalRand::NormalRand(double avg, double stddev, long seed) throw() - : average_(avg), standard_deviation_(stddev), randomizer_(seed), holder_(0.0), is_empty_(true) {} +NormalRand::NormalRand(double average, double standard_deviation, long seed) throw() + : average_(average), standard_deviation_(standard_deviation), randomizer_(seed), holder_(0.0), is_empty_(true) {} NormalRand::operator double() { if (is_empty_) { diff --git a/src/library/randomization/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp index 4d9a4f393..80954ba71 100644 --- a/src/library/randomization/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -28,19 +28,19 @@ class NormalRand { /** * @fn NormalRand * @brief Constructor - * @param avg: Average of normal distribution - * @param stddev: Standard deviation of normal distribution + * @param average: Average of normal distribution + * @param standard_deviation: Standard deviation of normal distribution */ - NormalRand(double avg, double stddev); + NormalRand(double average, double standard_deviation); /** * @fn NormalRand * @brief Constructor - * @param avg: Average of normal distribution - * @param stddev: Standard deviation of normal distribution + * @param average: Average of normal distribution + * @param standard_deviation: Standard deviation of normal distribution * @param seed: Seed of randomization */ - NormalRand(double avg, double stddev, long seed) throw(); + NormalRand(double average, double standard_deviation, long seed) throw(); /** * @fn Cast operator to double type @@ -50,44 +50,44 @@ class NormalRand { operator double(); /** - * @fn avg + * @fn average * @brief Return average */ - inline double avg() const; + inline double average() const; /** - * @fn avg + * @fn average * @brief Set average */ - inline void avg(double avg); + inline void average(double average); /** - * @fn stddev + * @fn standard_deviation * @brief Return standard deviation */ - inline double stddev() const; + inline double standard_deviation() const; /** - * @fn stddev + * @fn standard_deviation * @brief Set standard deviation */ - inline void stddev(double stddev); + inline void standard_deviation(double standard_deviation); /** * @fn set_param * @brief Set parameters - * @param avg: Average of normal distribution - * @param stddev: Standard deviation of normal distribution + * @param average: Average of normal distribution + * @param standard_deviation: Standard deviation of normal distribution */ - inline void set_param(double avg, double stddev); + inline void set_param(double average, double standard_deviation); /** * @fn set_param * @brief Set parameters - * @param avg: Average of normal distribution - * @param stddev: Standard deviation of normal distribution + * @param average: Average of normal distribution + * @param standard_deviation: Standard deviation of normal distribution * @param seed: Seed of randomization */ - inline void set_param(double avg, double stddev, long seed); + inline void set_param(double average, double standard_deviation, long seed); private: double average_; //!< Average diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp index 2db2f6206..8d18ecd7f 100644 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ b/src/library/randomization/normal_randomization_inline_functions.hpp @@ -8,22 +8,22 @@ namespace libra { -double NormalRand::avg() const { return average_; } +double NormalRand::average() const { return average_; } -void NormalRand::avg(double avg) { average_ = avg; } +void NormalRand::average(double average) { average_ = average; } -double NormalRand::stddev() const { return standard_deviation_; } +double NormalRand::standard_deviation() const { return standard_deviation_; } -void NormalRand::stddev(double stddev) { standard_deviation_ = stddev; } +void NormalRand::standard_deviation(double standard_deviation) { standard_deviation_ = standard_deviation; } -void NormalRand::set_param(double avg, double stddev) { - average_ = avg; - standard_deviation_ = stddev; +void NormalRand::set_param(double average, double standard_deviation) { + average_ = average; + standard_deviation_ = standard_deviation; } -void NormalRand::set_param(double avg, double stddev, long seed) { - average_ = avg; - standard_deviation_ = stddev; +void NormalRand::set_param(double average, double standard_deviation, long seed) { + average_ = average; + standard_deviation_ = standard_deviation; randomizer_.InitSeed(seed); } diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index 097a9ec09..7cb9db714 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -21,10 +21,10 @@ class RandomWalk : public libra::ODE { * @fn RandomWalk * @brief Constructor * @param step_width: Step width - * @param stddev: Standard deviation of random walk excitation noise + * @param standard_deviation: Standard deviation of random walk excitation noise * @param limit: Limit of random walk */ - RandomWalk(double step_width, const libra::Vector& stddev, const libra::Vector& limit); + RandomWalk(double step_width, const libra::Vector& standard_deviation, const libra::Vector& limit); /** * @fn RHS diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 5342c4830..e7ef6b1a5 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -10,11 +10,11 @@ #include template -RandomWalk::RandomWalk(double step_width, const libra::Vector& stddev, const libra::Vector& limit) +RandomWalk::RandomWalk(double step_width, const libra::Vector& standard_deviation, const libra::Vector& limit) : libra::ODE(step_width), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { - nrs_[i].set_param(0.0, stddev[i], global_randomization.MakeSeed()); + nrs_[i].set_param(0.0, standard_deviation[i], global_randomization.MakeSeed()); } } From e0d06fd64c23bd5d0a0d177df4aa1dbcc09e1444 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:23:04 +0100 Subject: [PATCH 0670/1086] Fix public function names --- .../base/sensor_template_functions.hpp | 2 +- src/components/ideal/force_generator.cpp | 2 +- src/components/ideal/torque_generator.cpp | 2 +- src/components/real/aocs/magnetorquer.cpp | 4 +-- src/components/real/aocs/sun_sensor.cpp | 4 +-- .../real/propulsion/simple_thruster.cpp | 4 +-- .../randomization/normal_randomization.hpp | 35 +++++++++++-------- .../normal_randomization_inline_functions.hpp | 23 +----------- .../random_walk_template_functions.hpp | 2 +- 9 files changed, 32 insertions(+), 46 deletions(-) diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index 11825c127..072e0a2a0 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -18,7 +18,7 @@ SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra:: bias_c_(bias_c), n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c) { for (size_t i = 0; i < N; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i], global_randomization.MakeSeed()); + nrs_c_[i].SetParameters(0.0, nr_stddev_c[i], global_randomization.MakeSeed()); } RangeCheck(); } diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 2e47cdbef..23e2f8a57 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -14,7 +14,7 @@ ForceGenerator::ForceGenerator(const int prescaler, ClockGenerator* clock_gen, c magnitude_noise_(0.0, magnitude_error_standard_deviation_N), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { - direction_noise_.set_param(0.0, 1.0); + direction_noise_.SetParameters(0.0, 1.0); } ForceGenerator::~ForceGenerator() {} diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 4e01c35c1..4702af48b 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -14,7 +14,7 @@ TorqueGenerator::TorqueGenerator(const int prescaler, ClockGenerator* clock_gen, magnitude_noise_(0.0, magnitude_error_standard_deviation_Nm), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { - direction_noise_.set_param(0.0, 1.0); + direction_noise_.SetParameters(0.0, 1.0); } TorqueGenerator::~TorqueGenerator() {} diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 015145a34..268487892 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -25,7 +25,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), mag_env_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + nrs_c_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } @@ -44,7 +44,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), mag_env_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].set_param(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + nrs_c_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index b605af4c0..94d206bb6 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -47,8 +47,8 @@ void SunSensor::Initialize(const double nr_stddev_c, const double nr_bias_stddev bias_beta_ += nr; // Normal Random - nrs_alpha_.set_param(0.0, nr_stddev_c); // global_randomization.MakeSeed() - nrs_beta_.set_param(0.0, nr_stddev_c); // global_randomization.MakeSeed() + nrs_alpha_.SetParameters(0.0, nr_stddev_c); // global_randomization.MakeSeed() + nrs_beta_.SetParameters(0.0, nr_stddev_c); // global_randomization.MakeSeed() } void SunSensor::MainRoutine(int count) { UNUSED(count); diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 75d22b852..23c2aaed7 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -40,8 +40,8 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, P SimpleThruster::~SimpleThruster() {} void SimpleThruster::Initialize(const double mag_err, const double dir_err) { - mag_nr_.set_param(0.0, mag_err); - dir_nr_.set_param(0.0, dir_err); + mag_nr_.SetParameters(0.0, mag_err); + dir_nr_.SetParameters(0.0, dir_err); thrust_dir_b_ = normalize(thrust_dir_b_); } diff --git a/src/library/randomization/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp index 80954ba71..af29d06bf 100644 --- a/src/library/randomization/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -50,44 +50,51 @@ class NormalRand { operator double(); /** - * @fn average + * @fn GetAverage * @brief Return average */ - inline double average() const; + inline double GetAverage() const { return average_; } /** - * @fn average - * @brief Set average + * @fn GetStandardDeviation + * @brief Return standard deviation */ - inline void average(double average); + inline double GetStandardDeviation() const { return standard_deviation_; } /** - * @fn standard_deviation - * @brief Return standard deviation + * @fn SetAverage + * @brief Set average */ - inline double standard_deviation() const; + inline void SetAverage(const double average) { average_ = average; } /** - * @fn standard_deviation + * @fn SetStandardDeviation * @brief Set standard deviation */ - inline void standard_deviation(double standard_deviation); + inline void SetStandardDeviation(const double standard_deviation) { standard_deviation_ = standard_deviation; } /** - * @fn set_param + * @fn SetParameter * @brief Set parameters * @param average: Average of normal distribution * @param standard_deviation: Standard deviation of normal distribution */ - inline void set_param(double average, double standard_deviation); + inline void SetParameters(const double average, const double standard_deviation) { + average_ = average; + standard_deviation_ = standard_deviation; + } /** - * @fn set_param + * @fn SetParameter * @brief Set parameters * @param average: Average of normal distribution * @param standard_deviation: Standard deviation of normal distribution * @param seed: Seed of randomization */ - inline void set_param(double average, double standard_deviation, long seed); + inline void SetParameters(const double average, const double standard_deviation, const long seed) { + average_ = average; + standard_deviation_ = standard_deviation; + randomizer_.InitSeed(seed); + } private: double average_; //!< Average diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp index 8d18ecd7f..05cbce71f 100644 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ b/src/library/randomization/normal_randomization_inline_functions.hpp @@ -6,27 +6,6 @@ #ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ #define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ -namespace libra { - -double NormalRand::average() const { return average_; } - -void NormalRand::average(double average) { average_ = average; } - -double NormalRand::standard_deviation() const { return standard_deviation_; } - -void NormalRand::standard_deviation(double standard_deviation) { standard_deviation_ = standard_deviation; } - -void NormalRand::set_param(double average, double standard_deviation) { - average_ = average; - standard_deviation_ = standard_deviation; -} - -void NormalRand::set_param(double average, double standard_deviation, long seed) { - average_ = average; - standard_deviation_ = standard_deviation; - randomizer_.InitSeed(seed); -} - -} // namespace libra +namespace libra {} // namespace libra #endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index e7ef6b1a5..597ddbac4 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -14,7 +14,7 @@ RandomWalk::RandomWalk(double step_width, const libra::Vector& standard_de : libra::ODE(step_width), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { - nrs_[i].set_param(0.0, standard_deviation[i], global_randomization.MakeSeed()); + nrs_[i].SetParameters(0.0, standard_deviation[i], global_randomization.MakeSeed()); } } From 889bcf7793a795006cedb711fc421d6be23b8098 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:23:57 +0100 Subject: [PATCH 0671/1086] Delete unnecessary file --- src/library/randomization/normal_randomization.hpp | 2 -- .../normal_randomization_inline_functions.hpp | 11 ----------- 2 files changed, 13 deletions(-) delete mode 100644 src/library/randomization/normal_randomization_inline_functions.hpp diff --git a/src/library/randomization/normal_randomization.hpp b/src/library/randomization/normal_randomization.hpp index af29d06bf..962126a0c 100644 --- a/src/library/randomization/normal_randomization.hpp +++ b/src/library/randomization/normal_randomization.hpp @@ -108,6 +108,4 @@ class NormalRand { } // namespace libra -#include "normal_randomization_inline_functions.hpp" - #endif // S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ diff --git a/src/library/randomization/normal_randomization_inline_functions.hpp b/src/library/randomization/normal_randomization_inline_functions.hpp deleted file mode 100644 index 05cbce71f..000000000 --- a/src/library/randomization/normal_randomization_inline_functions.hpp +++ /dev/null @@ -1,11 +0,0 @@ -/** - * @file normal_randomization_inline_functions.hpp - * @brief Class to generate random value with normal distribution with Box-Muller method - * @note Inline functions - */ -#ifndef S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ -#define S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ - -namespace libra {} // namespace libra - -#endif // S2E_LIBRARY_MATH_NORMAL_RANDOMIZATION_INLINE_FUNCTIONS_HPP_ From 0607795a2fe1d0056594a4c9dc9d4cc4cdd510ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:25:17 +0100 Subject: [PATCH 0672/1086] Fix private variables --- src/library/randomization/random_walk.hpp | 4 ++-- .../randomization/random_walk_template_functions.hpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index 7cb9db714..f8710e51d 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -36,8 +36,8 @@ class RandomWalk : public libra::ODE { virtual void RHS(double x, const libra::Vector& state, libra::Vector& rhs); private: - libra::Vector limit_; //!< Limit of random walk - libra::NormalRand nrs_[N]; //!< Random walk excitation noise + libra::Vector limit_; //!< Limit of random walk + libra::NormalRand normal_randomizer_[N]; //!< Random walk excitation noise }; #include "random_walk_template_functions.hpp" // template function definisions. diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 597ddbac4..82b2d1b48 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -14,7 +14,7 @@ RandomWalk::RandomWalk(double step_width, const libra::Vector& standard_de : libra::ODE(step_width), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { - nrs_[i].SetParameters(0.0, standard_deviation[i], global_randomization.MakeSeed()); + normal_randomizer_[i].SetParameters(0.0, standard_deviation[i], global_randomization.MakeSeed()); } } @@ -24,11 +24,11 @@ void RandomWalk::RHS(double x, const libra::Vector& state, libra::Vector limit_[i]) - rhs[i] = -fabs(nrs_[i]); + rhs[i] = -fabs(normal_randomizer_[i]); else if (state[i] < -limit_[i]) - rhs[i] = fabs(nrs_[i]); + rhs[i] = fabs(normal_randomizer_[i]); else - rhs[i] = nrs_[i]; + rhs[i] = normal_randomizer_[i]; } } From 77b22474b16de355e49a9b76082590fd98b174b8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:26:59 +0100 Subject: [PATCH 0673/1086] Fix function argument --- src/library/randomization/random_walk.hpp | 4 ++-- src/library/randomization/random_walk_template_functions.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index f8710e51d..0f6fcc22c 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -20,11 +20,11 @@ class RandomWalk : public libra::ODE { /** * @fn RandomWalk * @brief Constructor - * @param step_width: Step width + * @param step_width_s: Step width * @param standard_deviation: Standard deviation of random walk excitation noise * @param limit: Limit of random walk */ - RandomWalk(double step_width, const libra::Vector& standard_deviation, const libra::Vector& limit); + RandomWalk(double step_width_s, const libra::Vector& standard_deviation, const libra::Vector& limit); /** * @fn RHS diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 82b2d1b48..fdab6dd72 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -10,8 +10,8 @@ #include template -RandomWalk::RandomWalk(double step_width, const libra::Vector& standard_deviation, const libra::Vector& limit) - : libra::ODE(step_width), limit_(limit) { +RandomWalk::RandomWalk(double step_width_s, const libra::Vector& standard_deviation, const libra::Vector& limit) + : libra::ODE(step_width_s), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { normal_randomizer_[i].SetParameters(0.0, standard_deviation[i], global_randomization.MakeSeed()); From 107e8621fb4f1eaf20191f2303cbbb02c14461cb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:46:01 +0100 Subject: [PATCH 0674/1086] Fix function argument --- src/library/math/quaternion.cpp | 32 ++++++------ src/library/math/quaternion.hpp | 50 +++++++++---------- .../math/quaternion_inline_functions.hpp | 10 ++-- 3 files changed, 46 insertions(+), 46 deletions(-) diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 0d1ebbcb4..93c5bf348 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -11,27 +11,27 @@ namespace libra { -Quaternion::Quaternion(const Vector<3>& axis, double rot) { - rot *= 0.5; - q_[3] = cos(rot); +Quaternion::Quaternion(const Vector<3>& rotation_axis, double rotation_angle_rad) { + rotation_angle_rad *= 0.5; + q_[3] = cos(rotation_angle_rad); - // Vector<3> norm = normalize(axis); - // for(size_t i=0; i<3; ++i){ q_[i] = norm[i]*sin(rot); } + // Vector<3> norm = normalize(rotation_axis); + // for(size_t i=0; i<3; ++i){ q_[i] = norm[i]*sin(rotation_angle_rad); } for (size_t i = 0; i < 3; ++i) { - q_[i] = axis[i] * sin(rot); + q_[i] = rotation_axis[i] * sin(rotation_angle_rad); } } -Quaternion::Quaternion(const Vector<3>& v_before, const Vector<3>& v_after) { +Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_after) { // Assert for zero vector - assert(norm(v_before) > DBL_EPSILON); - assert(norm(v_after) > DBL_EPSILON); + assert(norm(vector_before) > DBL_EPSILON); + assert(norm(vector_after) > DBL_EPSILON); // Normalize - Vector<3> normalized_v_before = 1.0 / norm(v_before) * v_before; - Vector<3> normalized_v_after = 1.0 / norm(v_after) * v_after; + Vector<3> normalized_v_before = 1.0 / norm(vector_before) * vector_before; + Vector<3> normalized_v_after = 1.0 / norm(vector_after) * vector_after; // inner product (=cosine of the angle(theta) between two vectors) double ip = inner_product(normalized_v_before, normalized_v_after); - // outer product (rotation axis for converting v_before to v_after) + // outer product (rotation rotation_axis for converting vector_before to vector_after) Vector<3> op = outer_product(normalized_v_before, normalized_v_after); if (ip > 1.0 - DBL_EPSILON) { // if theta=0, then rotation is not need @@ -40,8 +40,8 @@ Quaternion::Quaternion(const Vector<3>& v_before, const Vector<3>& v_after) { q_[2] = 0.0; q_[3] = 1.0; } else if (ip < -1.0 + DBL_EPSILON) { - // if theta=180deg, the rotation axis can't be defined, so rotate v_before manually - Vector<3> rotation_axis = GenerateOrthoUnitVector(v_before); + // if theta=180deg, the rotation rotation_axis can't be defined, so rotate vector_before manually + Vector<3> rotation_axis = GenerateOrthoUnitVector(vector_before); q_[0] = rotation_axis[0], q_[1] = rotation_axis[1], q_[2] = rotation_axis[2], q_[3] = 0.0; } else { assert(norm(op) > 0.0); @@ -223,9 +223,9 @@ Vector<3> Quaternion::frame_conv(const Vector<3>& v) const { return ans; } -Vector<3> Quaternion::frame_conv_inv(const Vector<3>& cv) const { +Vector<3> Quaternion::frame_conv_inv(const Vector<3>& quaternion_vector) const { Quaternion conj = conjugate(); - Quaternion temp1 = q_ * cv; + Quaternion temp1 = q_ * quaternion_vector; Quaternion temp2 = temp1 * conj; Vector<3> ans; for (int i = 0; i < 3; ++i) { diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 4bb5334f3..eac11802e 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -25,40 +25,40 @@ class Quaternion { /** * @fn Quaternion * @brief Constructor with initialization - * @param [in] q0: The first element of Quaternion (X) - * @param [in] q1: The second element of Quaternion (Y) - * @param [in] q2: The third element of Quaternion (Z) - * @param [in] q3: The fourth element of Quaternion (W) + * @param [in] q_x: The first element of Quaternion (X) + * @param [in] q_y: The second element of Quaternion (Y) + * @param [in] q_z: The third element of Quaternion (Z) + * @param [in] q_w: The fourth element of Quaternion (W) */ - inline Quaternion(double q0, double q1, double q2, double q3); + inline Quaternion(double q_x, double q_y, double q_z, double q_w); /** * @fn Quaternion * @brief Constructor initialized with vector - * @param [in] cv: Vector storing quaternion + * @param [in] quaternion_vector: Vector storing quaternion */ - inline Quaternion(const Vector<4>& cv); + inline Quaternion(const Vector<4>& quaternion_vector); /** * @fn Quaternion * @brief Constructor initialized with rotation expression - * @param [in] axis: Rotation axis normalized vector - * @param [in] rot: Rotation angle [rad] + * @param [in] rotation_axis: Rotation axis normalized vector + * @param [in] rotation_angle_rad: Rotation angle [rad] */ - Quaternion(const Vector<3>& axis, double rot); + Quaternion(const Vector<3>& rotation_axis, double rotation_angle_rad); /** * @fn Quaternion - * @brief Constructor initialized with rotates v_before to match v_after - * @param [in] v_before: Vector before rotation - * @param [in] v_after: Vector after rotation + * @brief Constructor initialized with rotates vector_before to match vector_after + * @param [in] vector_before: Vector before rotation + * @param [in] vector_after: Vector after rotation */ - Quaternion(const Vector<3>& v_before, const Vector<3>& v_after); + Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_after); /** * @fn Operator = * @brief Substitute Vector value to Quaternion - * @param [in] cv: Vector + * @param [in] quaternion_vector: Vector * @return Quaternion */ - inline Quaternion& operator=(const Vector<4>& cv); + inline Quaternion& operator=(const Vector<4>& quaternion_vector); /** * @fn Cast operator to const Vector<4> @@ -71,12 +71,12 @@ class Quaternion { /** * @fn set * @brief Set the quaternion elements - * @param [in] q0: The first element of Quaternion (X) - * @param [in] q1: The second element of Quaternion (Y) - * @param [in] q2: The third element of Quaternion (Z) - * @param [in] q3: The fourth element of Quaternion (W) + * @param [in] q_x: The first element of Quaternion (X) + * @param [in] q_y: The second element of Quaternion (Y) + * @param [in] q_z: The third element of Quaternion (Z) + * @param [in] q_w: The fourth element of Quaternion (W) */ - void set(double q0 = 0.0, double q1 = 0.0, double q2 = 0.0, double q3 = 1.0); + void set(double q_x = 0.0, double q_y = 0.0, double q_z = 0.0, double q_w = 1.0); /** * @fn Cast operator @@ -137,18 +137,18 @@ class Quaternion { /** * @fn frame_conv * @brief Frame conversion for the given target vector with the quaternion - * @param [in] cv: Target vector + * @param [in] quaternion_vector: Target vector * @return Converted vector */ - Vector<3> frame_conv(const Vector<3>& cv) const; + Vector<3> frame_conv(const Vector<3>& quaternion_vector) const; /** * @fn frame_conv_inv * @brief Frame conversion for the given target vector with the inverse quaternion - * @param [in] cv: Target vector + * @param [in] quaternion_vector: Target vector * @return Converted vector */ - Vector<3> frame_conv_inv(const Vector<3>& cv) const; + Vector<3> frame_conv_inv(const Vector<3>& quaternion_vector) const; /** * @fn toVector diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index 296c8b036..173358027 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -10,11 +10,11 @@ namespace libra { Quaternion::Quaternion() {} -Quaternion::Quaternion(double q0, double q1, double q2, double q3) { - q_[0] = q0; - q_[1] = q1; - q_[2] = q2; - q_[3] = q3; +Quaternion::Quaternion(double q_x, double q_y, double q_z, double q_w) { + q_[0] = q_x; + q_[1] = q_y; + q_[2] = q_z; + q_[3] = q_w; } Quaternion::Quaternion(const Vector<4>& q) : q_(q) {} From eac7cff159127709c95409a8abb43559130439f6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:49:45 +0100 Subject: [PATCH 0675/1086] Fix function argument --- src/library/math/quaternion.cpp | 8 ++++---- src/library/math/quaternion.hpp | 8 ++++---- src/library/math/quaternion_inline_functions.hpp | 6 +++--- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 93c5bf348..97fa7145c 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -212,9 +212,9 @@ Quaternion Quaternion::fromEuler(Vector<3> euler) { return Quaternion::fromDCM(dcm); } -Vector<3> Quaternion::frame_conv(const Vector<3>& v) const { +Vector<3> Quaternion::frame_conv(const Vector<3>& vector) const { Quaternion conj = conjugate(); - Quaternion temp1 = conj * v; + Quaternion temp1 = conj * vector; Quaternion temp2 = temp1 * q_; Vector<3> ans; for (int i = 0; i < 3; ++i) { @@ -223,9 +223,9 @@ Vector<3> Quaternion::frame_conv(const Vector<3>& v) const { return ans; } -Vector<3> Quaternion::frame_conv_inv(const Vector<3>& quaternion_vector) const { +Vector<3> Quaternion::frame_conv_inv(const Vector<3>& vector) const { Quaternion conj = conjugate(); - Quaternion temp1 = q_ * quaternion_vector; + Quaternion temp1 = q_ * vector; Quaternion temp2 = temp1 * conj; Vector<3> ans; for (int i = 0; i < 3; ++i) { diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index eac11802e..48fce30c2 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -137,18 +137,18 @@ class Quaternion { /** * @fn frame_conv * @brief Frame conversion for the given target vector with the quaternion - * @param [in] quaternion_vector: Target vector + * @param [in] vector: Target vector * @return Converted vector */ - Vector<3> frame_conv(const Vector<3>& quaternion_vector) const; + Vector<3> frame_conv(const Vector<3>& vector) const; /** * @fn frame_conv_inv * @brief Frame conversion for the given target vector with the inverse quaternion - * @param [in] quaternion_vector: Target vector + * @param [in] vector: Target vector * @return Converted vector */ - Vector<3> frame_conv_inv(const Vector<3>& quaternion_vector) const; + Vector<3> frame_conv_inv(const Vector<3>& vector) const; /** * @fn toVector diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index 173358027..c48440a14 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -17,10 +17,10 @@ Quaternion::Quaternion(double q_x, double q_y, double q_z, double q_w) { q_[3] = q_w; } -Quaternion::Quaternion(const Vector<4>& q) : q_(q) {} +Quaternion::Quaternion(const Vector<4>& quaternion_vector) : q_(quaternion_vector) {} -Quaternion& Quaternion::operator=(const Vector<4>& q) { - q_ = q; +Quaternion& Quaternion::operator=(const Vector<4>& quaternion_vector) { + q_ = quaternion_vector; return *this; } From bbf509c2e5589a8136307ac4454c10810b9bfc33 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 21:52:15 +0100 Subject: [PATCH 0676/1086] Delete unused public function --- src/library/math/quaternion.hpp | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 48fce30c2..d6902e977 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -68,16 +68,6 @@ class Quaternion { */ inline operator const Vector<4>&() const; - /** - * @fn set - * @brief Set the quaternion elements - * @param [in] q_x: The first element of Quaternion (X) - * @param [in] q_y: The second element of Quaternion (Y) - * @param [in] q_z: The third element of Quaternion (Z) - * @param [in] q_w: The fourth element of Quaternion (W) - */ - void set(double q_x = 0.0, double q_y = 0.0, double q_z = 0.0, double q_w = 1.0); - /** * @fn Cast operator * @brief Operator to directly access the element like array with [] operator From 6aaf5fbdb3feb6d4ff962eefd297c1006ceccde9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Feb 2023 22:15:01 +0100 Subject: [PATCH 0677/1086] Fix public function name --- src/components/ideal/force_generator.cpp | 12 +++--- src/components/ideal/torque_generator.cpp | 2 +- src/components/real/aocs/gnss_receiver.cpp | 14 +++---- src/components/real/aocs/gyro_sensor.cpp | 4 +- .../real/aocs/initialize_reaction_wheel.cpp | 2 +- src/components/real/aocs/magnetometer.cpp | 4 +- src/components/real/aocs/magnetorquer.cpp | 6 +-- src/components/real/aocs/reaction_wheel.cpp | 2 +- .../real/aocs/reaction_wheel_jitter.cpp | 8 ++-- src/components/real/aocs/star_sensor.cpp | 12 +++--- src/components/real/aocs/sun_sensor.cpp | 2 +- src/components/real/aocs/sun_sensor.hpp | 2 +- .../ground_station_calculator.cpp | 4 +- src/components/real/mission/telescope.cpp | 14 +++---- .../real/propulsion/simple_thruster.cpp | 6 +-- src/dynamics/attitude/attitude.cpp | 4 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 4 +- src/dynamics/orbit/orbit.cpp | 4 +- src/dynamics/orbit/orbit.hpp | 4 +- src/dynamics/orbit/relative_orbit.cpp | 12 +++--- .../global/hipparcos_catalogue.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- .../local/local_celestial_information.cpp | 4 +- src/library/geodesy/geodetic_position.cpp | 2 +- src/library/math/quaternion.cpp | 26 ++++++------- src/library/math/quaternion.hpp | 38 +++++++++---------- .../ground_station/ground_station.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 6 +-- .../relative_information.cpp | 6 +-- 30 files changed, 106 insertions(+), 106 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 23e2f8a57..2ff0271b1 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -30,7 +30,7 @@ void ForceGenerator::MainRoutine(int count) { // Add noise only when the force is generated libra::Vector<3> true_direction = normalize(generated_force_b_N_); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); - libra::Vector<3> converted_direction = error_quaternion.frame_conv(generated_force_b_N_); + libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_force_b_N_); double force_norm_with_error = norm_ordered_force + magnitude_noise_; generated_force_b_N_ = force_norm_with_error * converted_direction; } @@ -38,8 +38,8 @@ void ForceGenerator::MainRoutine(int count) { // Convert frame libra::Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternion_i2lvlh(); - generated_force_i_N_ = q_i2b.frame_conv_inv(generated_force_b_N_); - generated_force_rtn_N_ = q_i2rtn.frame_conv(generated_force_i_N_); + generated_force_i_N_ = q_i2b.InverseFrameConversion(generated_force_b_N_); + generated_force_rtn_N_ = q_i2rtn.FrameConversion(generated_force_i_N_); } void ForceGenerator::PowerOffRoutine() { @@ -50,15 +50,15 @@ void ForceGenerator::PowerOffRoutine() { void ForceGenerator::SetForce_i_N(const libra::Vector<3> force_i_N) { libra::Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); - ordered_force_b_N_ = q_i2b.frame_conv(force_i_N); + ordered_force_b_N_ = q_i2b.FrameConversion(force_i_N); } void ForceGenerator::SetForce_rtn_N(const libra::Vector<3> force_rtn_N) { libra::Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); libra::Quaternion q_i2rtn = dynamics_->GetOrbit().CalcQuaternion_i2lvlh(); - libra::Vector<3> force_i_N = q_i2rtn.frame_conv_inv(force_rtn_N); - ordered_force_b_N_ = q_i2b.frame_conv(force_i_N); + libra::Vector<3> force_i_N = q_i2rtn.InverseFrameConversion(force_rtn_N); + ordered_force_b_N_ = q_i2b.FrameConversion(force_i_N); } std::string ForceGenerator::GetLogHeader() const { diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 4702af48b..894b95276 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -30,7 +30,7 @@ void TorqueGenerator::MainRoutine(int count) { // Add noise only when the torque is generated libra::Vector<3> true_direction = normalize(generated_torque_b_Nm_); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); - libra::Vector<3> converted_direction = error_quaternion.frame_conv(generated_torque_b_Nm_); + libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_torque_b_Nm_); double torque_norm_with_error = norm_ordered_torque + magnitude_noise_; generated_torque_b_Nm_ = torque_norm_with_error * converted_direction; } diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 597ad5940..5765b76df 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -82,8 +82,8 @@ void GNSSReceiver::CheckAntennaSimple(const Vector<3> pos_true_eci_, Quaternion // antenna normal vector at inertial frame Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - Vector<3> antenna_direction_b = q_b2c_.frame_conv_inv(antenna_direction_c); - Vector<3> antenna_direction_i = q_i2b.frame_conv_inv(antenna_direction_b); + Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); double inner = inner_product(pos_true_eci_, antenna_direction_i); if (inner <= 0) @@ -100,10 +100,10 @@ void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_ // antenna normal vector at inertial frame Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - Vector<3> antenna_direction_b = q_b2c_.frame_conv_inv(antenna_direction_c); - Vector<3> antenna_direction_i = q_i2b.frame_conv_inv(antenna_direction_b); + Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); - sat2ant_i = q_i2b.frame_conv_inv(antenna_position_b_); + sat2ant_i = q_i2b.InverseFrameConversion(antenna_position_b_); ant_pos_i = pos_true_eci_ + sat2ant_i; // initialize @@ -155,8 +155,8 @@ void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_ void GNSSReceiver::SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::string gnss_id) { Vector<3> ant2gnss_b, ant2gnss_c; - ant2gnss_b = q_i2b.frame_conv(ant2gnss_i); - ant2gnss_c = q_b2c_.frame_conv(ant2gnss_b); + ant2gnss_b = q_i2b.FrameConversion(ant2gnss_i); + ant2gnss_c = q_b2c_.FrameConversion(ant2gnss_b); double dist = norm(ant2gnss_c); double lon = AcTan(ant2gnss_c[1], ant2gnss_c[0]); diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index bc1b822eb..6eb3d1b4d 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -18,8 +18,8 @@ Gyro::~Gyro() {} void Gyro::MainRoutine(int count) { UNUSED(count); - omega_c_ = q_b2c_.frame_conv(dynamics_->GetAttitude().GetOmega_b()); // Convert frame - omega_c_ = Measure(omega_c_); // Add noises + omega_c_ = q_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame + omega_c_ = Measure(omega_c_); // Add noises } std::string Gyro::GetLogHeader() const { diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index a15c38819..cdfc0646f 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -64,7 +64,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double libra::Vector<3> direction_c(0.0); direction_c[2] = 1.0; libra::Quaternion q(direction_b, direction_c); - q_b2c = q.conjugate(); + q_b2c = q.Conjugate(); } rwmodel_conf.ReadVector(RWsection, "position_b_m", pos_b); diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 2f7d378dc..a9c19c5e1 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -17,8 +17,8 @@ MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = q_b2c_.frame_conv(magnet_->GetGeomagneticFieldneticField_b_nT()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + mag_c_ = q_b2c_.FrameConversion(magnet_->GetGeomagneticFieldneticField_b_nT()); // Convert frame + mag_c_ = Measure(mag_c_); // Add noises } std::string MagSensor::GetLogHeader() const { diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 268487892..b02fadcb6 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -17,7 +17,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int : ComponentBase(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), - q_c2b_(q_b2c_.conjugate()), + q_c2b_(q_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), min_c_(min_c), @@ -36,7 +36,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort : ComponentBase(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), - q_c2b_(q_b2c_.conjugate()), + q_c2b_(q_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), min_c_(min_c), @@ -72,7 +72,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { mag_moment_c_ = scale_factor_ * mag_moment_c_; // Frame conversion component to body - mag_moment_b_ = q_c2b_.frame_conv(mag_moment_c_); + mag_moment_b_ = q_c2b_.FrameConversion(mag_moment_c_); // Calc magnetic torque [Nm] torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetGeomagneticFieldneticField_b_nT()); // Update Random Walk diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 53e04c801..77582176f 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -75,7 +75,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, P void RWModel::Initialize() { direction_c_ = libra::Vector<3>(0.0); direction_c_[2] = 1.0; - direction_b_ = q_b2c_.frame_conv_inv(direction_c_); + direction_b_ = q_b2c_.InverseFrameConversion(direction_c_); velocity_limit_rpm_ = max_velocity_rpm_; output_torque_b_ = libra::Vector<3>(0.0); diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 27a9a73a1..6fa23f5f4 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -71,11 +71,11 @@ void RWJitter::CalcJitter(double angular_velocity_rad) { // Add structural resonance if (considers_structural_resonance_) { AddStructuralResonance(); - jitter_force_b_ = q_b2c_.frame_conv_inv(filtered_jitter_force_n_c_); - jitter_torque_b_ = q_b2c_.frame_conv_inv(filtered_jitter_torque_n_c_); + jitter_force_b_ = q_b2c_.InverseFrameConversion(filtered_jitter_force_n_c_); + jitter_torque_b_ = q_b2c_.InverseFrameConversion(filtered_jitter_torque_n_c_); } else { - jitter_force_b_ = q_b2c_.frame_conv_inv(unfiltered_jitter_force_n_c_); - jitter_torque_b_ = q_b2c_.frame_conv_inv(unfiltered_jitter_torque_n_c_); + jitter_force_b_ = q_b2c_.InverseFrameConversion(unfiltered_jitter_force_n_c_); + jitter_torque_b_ = q_b2c_.InverseFrameConversion(unfiltered_jitter_torque_n_c_); } } diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 7621f50fb..87ead57c2 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -134,8 +134,8 @@ void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const } int STT::SunJudgement(const libra::Vector<3>& sun_b) { - Quaternion q_c2b = q_b2c_.conjugate(); - Vector<3> sight_b = q_c2b.frame_conv(sight_); + Quaternion q_c2b = q_b2c_.Conjugate(); + Vector<3> sight_b = q_c2b.FrameConversion(sight_); double sun_angle_rad = CalAngleVect_rad(sun_b, sight_b); if (sun_angle_rad < sun_forbidden_angle_) return 1; @@ -144,8 +144,8 @@ int STT::SunJudgement(const libra::Vector<3>& sun_b) { } int STT::EarthJudgement(const libra::Vector<3>& earth_b) { - Quaternion q_c2b = q_b2c_.conjugate(); - Vector<3> sight_b = q_c2b.frame_conv(sight_); + Quaternion q_c2b = q_b2c_.Conjugate(); + Vector<3> sight_b = q_c2b.FrameConversion(sight_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, norm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge double earth_center_angle_rad = CalAngleVect_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight @@ -157,8 +157,8 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { } int STT::MoonJudgement(const libra::Vector<3>& moon_b) { - Quaternion q_c2b = q_b2c_.conjugate(); - Vector<3> sight_b = q_c2b.frame_conv(sight_); + Quaternion q_c2b = q_b2c_.Conjugate(); + Vector<3> sight_b = q_c2b.FrameConversion(sight_); double moon_angle_rad = CalAngleVect_rad(moon_b, sight_b); if (moon_angle_rad < moon_forbidden_angle_) return 1; diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 94d206bb6..a104c2cbd 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -60,7 +60,7 @@ void SunSensor::measure() { libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = normalize(sun_pos_b); - sun_c_ = q_b2c_.frame_conv(sun_dir_b); // Frame conversion from body to component + sun_c_ = q_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component SunDetectionJudgement(); // Judge the sun is inside the FoV diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index aef5a6b63..04a0a941f 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -80,7 +80,7 @@ class SunSensor : public ComponentBase, public ILoggable { // Getter inline bool GetSunDetectedFlag() const { return sun_detected_flag_; }; inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_c_; }; - inline const libra::Vector<3> GetMeasuredSun_b() const { return q_b2c_.conjugate().frame_conv(measured_sun_c_); }; + inline const libra::Vector<3> GetMeasuredSun_b() const { return q_b2c_.Conjugate().FrameConversion(measured_sun_c_); }; inline double GetSunAngleAlpha() const { return alpha_; }; inline double GetSunAngleBeta() const { return beta_; }; inline double GetSolarIlluminance() const { return solar_illuminance_; }; diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 6b53caeae..d75c33b17 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -74,7 +74,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; sc_to_gs_i = libra::normalize(sc_to_gs_i); Quaternion q_i_to_sc_ant = sc_tx_ant.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); - Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.frame_conv(sc_to_gs_i); + Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_ant_rad = acos(gs_direction_on_sc_frame[2]); double phi_on_sc_ant_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_ant_rad)); @@ -82,7 +82,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); gs_to_sc_ecef = libra::normalize(gs_to_sc_ecef); Quaternion q_ecef_to_gs_ant = gs_rx_ant.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); - Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.frame_conv(gs_to_sc_ecef); + Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_ant_rad = acos(sc_direction_on_gs_frame[2]); double phi_on_gs_ant_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_ant_rad)); diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index a3aafb27c..1ee407d02 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -70,17 +70,17 @@ void Telescope::MainRoutine(int count) { // No update when Hipparocos Catalogue was not readed if (hipp_->IsCalcEnabled) ObserveStars(); // Debug ****************************************************************** - // sun_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); - // earth_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); - // moon_pos_c = q_b2c_.frame_conv(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); + // sun_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); + // earth_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); + // moon_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); // angle_sun = angle(sight_, sun_pos_c) * 180/libra::pi; // angle_earth = angle(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = angle(sight_, moon_pos_c) * 180 / libra::pi; //****************************************************************************** } bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { - Quaternion q_c2b = q_b2c_.conjugate(); - Vector<3> sight_b = q_c2b.frame_conv(sight_); + Quaternion q_c2b = q_b2c_.Conjugate(); + Vector<3> sight_b = q_c2b.FrameConversion(sight_); double angle_rad = libra::angle(target_b, sight_b); if (angle_rad < forbidden_angle) { return true; @@ -89,7 +89,7 @@ bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const doub } void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b) { - Vector<3, double> target_c = q_b2c_.frame_conv(target_b); + Vector<3, double> target_c = q_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame @@ -110,7 +110,7 @@ void Telescope::ObserveStars() { while (star_in_sight.size() < num_of_logged_stars_) { Vector<3> target_b = hipp_->GetStarDirection_b(count, q_i2b); - Vector<3> target_c = q_b2c_.frame_conv(target_b); + Vector<3> target_c = q_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 23c2aaed7..2e5953392 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -108,10 +108,10 @@ Vector<3> SimpleThruster::CalcThrustDir() { } Quaternion make_axis_rot(thrust_dir_b_true, make_axis_rot_rad); - Vector<3> axis_rot = make_axis_rot.frame_conv(ex); + Vector<3> axis_rot = make_axis_rot.FrameConversion(ex); - Quaternion err_rot(axis_rot, dir_nr_); // Generate error quaternion - thrust_dir_b_true = err_rot.frame_conv(thrust_dir_b_true); // Add error + Quaternion err_rot(axis_rot, dir_nr_); // Generate error quaternion + thrust_dir_b_true = err_rot.FrameConversion(thrust_dir_b_true); // Add error } return thrust_dir_b_true; diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 96311b4cc..a8e13a83a 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -47,8 +47,8 @@ void Attitude::SetParameters(const MCSimExecutor& mc_simulator) { GetInitParamet void Attitude::CalcAngularMomentum(void) { angular_momentum_spacecraft_b_Nms_ = inertia_tensor_kgm2_ * angular_velocity_b_rad_s_; angular_momentum_total_b_Nms_ = angular_momentum_reaction_wheel_b_Nms_ + angular_momentum_spacecraft_b_Nms_; - libra::Quaternion q_b2i = quaternion_i2b_.conjugate(); - angular_momentum_total_i_Nms_ = q_b2i.frame_conv(angular_momentum_total_b_Nms_); + libra::Quaternion q_b2i = quaternion_i2b_.Conjugate(); + angular_momentum_total_i_Nms_ = q_b2i.FrameConversion(angular_momentum_total_b_Nms_); angular_momentum_total_Nms_ = norm(angular_momentum_total_i_Nms_); kinetic_energy_J_ = 0.5 * libra::inner_product(angular_momentum_spacecraft_b_Nms_, angular_velocity_b_rad_s_); diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 51b34f5df..f9caac4b5 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -133,5 +133,5 @@ void AttitudeRk4::RungeKuttaOneStep(double t, double dt) { for (int i = 0; i < 4; i++) { quaternion_i2b_[i] = next_x[i + 3]; } - quaternion_i2b_.normalize(); + quaternion_i2b_.Normalize(); } diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 497f38cf0..de67fe7e4 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -101,7 +101,7 @@ void ControlledAttitude::PointingControl(const libra::Vector<3> main_direction_i // Calc DCM ECI->body libra::Matrix<3, 3> dcm_i2b = dcm_t2b * transpose(dcm_t2i); // Convert to Quaternion - quaternion_i2b_ = Quaternion::fromDCM(dcm_i2b); + quaternion_i2b_ = Quaternion::ConvertFromDcm(dcm_i2b); } libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_direction, const libra::Vector<3> sub_direction) { @@ -145,7 +145,7 @@ void ControlledAttitude::CalcAngularVelocity(const double current_time_s) { if (previous_calc_time_s_ > 0.0) { double time_diff_sec = current_time_s - previous_calc_time_s_; - libra::Quaternion prev_q_b2i = previous_quaternion_i2b_.conjugate(); + libra::Quaternion prev_q_b2i = previous_quaternion_i2b_.Conjugate(); libra::Quaternion q_diff = prev_q_b2i * quaternion_i2b_; q_diff = (2.0 / time_diff_sec) * q_diff; diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 585306d9d..6bf7bdc37 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -24,8 +24,8 @@ libra::Quaternion Orbit::CalcQuaternion_i2lvlh() const { dcm_i2lvlh[2][1] = lvlh_ez[1]; dcm_i2lvlh[2][2] = lvlh_ez[2]; - libra::Quaternion q_i2lvlh = libra::Quaternion::fromDCM(dcm_i2lvlh); - return q_i2lvlh.normalize(); + libra::Quaternion q_i2lvlh = libra::Quaternion::ConvertFromDcm(dcm_i2lvlh); + return q_i2lvlh.Normalize(); } void Orbit::TransformEciToEcef(void) { diff --git a/src/dynamics/orbit/orbit.hpp b/src/dynamics/orbit/orbit.hpp index 53b6952a6..591f79ee8 100644 --- a/src/dynamics/orbit/orbit.hpp +++ b/src/dynamics/orbit/orbit.hpp @@ -70,7 +70,7 @@ class Orbit : public ILoggable { * @param [in] quaternion_i2b: End time of simulation [sec] */ inline void UpdateByAttitude(const libra::Quaternion quaternion_i2b) { - spacecraft_velocity_b_m_s_ = quaternion_i2b.frame_conv(spacecraft_velocity_i_m_s_); + spacecraft_velocity_b_m_s_ = quaternion_i2b.FrameConversion(spacecraft_velocity_i_m_s_); } // Getters @@ -162,7 +162,7 @@ class Orbit : public ILoggable { * @param [in] spacecraft_mass_kg: Mass of spacecraft [kg] */ inline void AddForce_b_N(const libra::Vector<3> force_b_N, const libra::Quaternion quaternion_i2b, const double spacecraft_mass_kg) { - auto force_i = quaternion_i2b.frame_conv_inv(force_b_N); + auto force_i = quaternion_i2b.InverseFrameConversion(force_b_N); AddForce_i_N(force_i, spacecraft_mass_kg); } diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 60e038c43..1f735a2bc 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -42,9 +42,9 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l libra::Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); libra::Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); - libra::Quaternion q_lvlh2i = q_i2lvlh.conjugate(); - spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; - spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; + libra::Quaternion q_lvlh2i = q_i2lvlh.Conjugate(); + spacecraft_position_i_m_ = q_lvlh2i.FrameConversion(relative_position_lvlh_m_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.FrameConversion(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; initial_state_[0] = relative_position_lvlh_m[0]; initial_state_[1] = relative_position_lvlh_m[1]; @@ -110,10 +110,10 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { libra::Vector<3> reference_sat_velocity_i = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().GetVelocity_i_m_s(); libra::Quaternion q_i2lvlh = relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit().CalcQuaternion_i2lvlh(); - libra::Quaternion q_lvlh2i = q_i2lvlh.conjugate(); + libra::Quaternion q_lvlh2i = q_i2lvlh.Conjugate(); - spacecraft_position_i_m_ = q_lvlh2i.frame_conv(relative_position_lvlh_m_) + reference_sat_position_i; - spacecraft_velocity_i_m_s_ = q_lvlh2i.frame_conv(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; + spacecraft_position_i_m_ = q_lvlh2i.FrameConversion(relative_position_lvlh_m_) + reference_sat_position_i; + spacecraft_velocity_i_m_s_ = q_lvlh2i.FrameConversion(relative_velocity_lvlh_m_s_) + reference_sat_velocity_i; TransformEciToEcef(); TransformEcefToGeodetic(); } diff --git a/src/environment/global/hipparcos_catalogue.cpp b/src/environment/global/hipparcos_catalogue.cpp index 9bba26564..d973422a6 100644 --- a/src/environment/global/hipparcos_catalogue.cpp +++ b/src/environment/global/hipparcos_catalogue.cpp @@ -66,7 +66,7 @@ libra::Vector<3> HipparcosCatalogue::GetStarDirection_b(int rank, libra::Quatern libra::Vector<3> direction_b; direction_i = GetStarDirection_i(rank); - direction_b = quaternion_i2b.frame_conv(direction_i); + direction_b = quaternion_i2b.FrameConversion(direction_i); return direction_b; } diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index e6a6ce75f..b8ecb0cbf 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -36,7 +36,7 @@ void GeomagneticField::CalcMagneticField(const double decimal_year, const double for (int i = 0; i < 3; ++i) { magnetic_field_i_nT_[i] = magnetic_field_array_i_nT[i]; } - magnetic_field_b_nT_ = quaternion_i2b.frame_conv(magnetic_field_i_nT_); + magnetic_field_b_nT_ = quaternion_i2b.FrameConversion(magnetic_field_i_nT_); } void GeomagneticField::AddNoise(double* magnetic_field_array_i_nT) { diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 2449d66ff..2fbc8ca81 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -93,7 +93,7 @@ void LocalCelestialInformation::ConvertInertialToBody(const double* input_i, dou for (int i = 0; i < 3; i++) { temp_i[i] = input_i[i]; } - libra::Vector<3> temp_b = quaternion_i2b.frame_conv(temp_i); + libra::Vector<3> temp_b = quaternion_i2b.FrameConversion(temp_i); for (int i = 0; i < 3; i++) { output_b[i] = temp_b[i]; } @@ -124,7 +124,7 @@ void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* posi vi[i] = vi[i] - wxposition_i[i]; } // convert vector in inertial coordinate into that in body coordinate - libra::Vector<3> temp_b = quaternion_i2b.frame_conv(vi); + libra::Vector<3> temp_b = quaternion_i2b.FrameConversion(vi); for (int i = 0; i < 3; i++) { velocity_b[i] = temp_b[i]; } diff --git a/src/library/geodesy/geodetic_position.cpp b/src/library/geodesy/geodetic_position.cpp index b3ec4eece..1cb8c6abc 100644 --- a/src/library/geodesy/geodetic_position.cpp +++ b/src/library/geodesy/geodetic_position.cpp @@ -81,5 +81,5 @@ void GeodeticPosition::CalcQuaternionXcxfToLtc() { dcm_xcxf_to_ltc[2][1] = cos(latitude_rad_) * sin(longitude_rad_); dcm_xcxf_to_ltc[2][2] = sin(latitude_rad_); - quaternion_xcxf_to_ltc_ = quaternion_xcxf_to_ltc_.fromDCM(dcm_xcxf_to_ltc); + quaternion_xcxf_to_ltc_ = quaternion_xcxf_to_ltc_.ConvertFromDcm(dcm_xcxf_to_ltc); } diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 97fa7145c..c8af5c26c 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -100,7 +100,7 @@ Quaternion operator*(const double& lhs, const Quaternion& rhs) { return temp; } -Quaternion Quaternion::normalize(void) { +Quaternion Quaternion::Normalize(void) { double n = 0.0; for (int i = 0; i < 4; ++i) { n += pow(q_[i], 2.0); @@ -117,7 +117,7 @@ Quaternion Quaternion::normalize(void) { return q_; } -Quaternion Quaternion::conjugate(void) const { +Quaternion Quaternion::Conjugate(void) const { Quaternion temp(q_); for (int i = 0; i < 3; ++i) { temp[i] *= -1.0; @@ -125,7 +125,7 @@ Quaternion Quaternion::conjugate(void) const { return temp; } -Matrix<3, 3> Quaternion::toDCM(void) const { +Matrix<3, 3> Quaternion::ConvertToDcm(void) const { Matrix<3, 3> dcm; dcm[0][0] = q_[3] * q_[3] + q_[0] * q_[0] - q_[1] * q_[1] - q_[2] * q_[2]; @@ -143,7 +143,7 @@ Matrix<3, 3> Quaternion::toDCM(void) const { return dcm; } -Quaternion Quaternion::fromDCM(Matrix<3, 3> dcm) { +Quaternion Quaternion::ConvertFromDcm(Matrix<3, 3> dcm) { Quaternion q; q[0] = sqrt(1 + dcm[0][0] - dcm[1][1] - dcm[2][2]) / 2; q[1] = sqrt(1 - dcm[0][0] + dcm[1][1] - dcm[2][2]) / 2; @@ -184,8 +184,8 @@ Quaternion Quaternion::fromDCM(Matrix<3, 3> dcm) { return q; } -Vector<3> Quaternion::toEuler(void) const { - auto dcm = this->toDCM(); +Vector<3> Quaternion::ConvertToEuler(void) const { + auto dcm = this->ConvertToDcm(); Vector<3> eul; eul[0] = atan2(dcm[1][2], dcm[2][2]); eul[1] = atan2(-dcm[0][2], sqrt(dcm[1][2] * dcm[1][2] + dcm[2][2] * dcm[2][2])); @@ -193,7 +193,7 @@ Vector<3> Quaternion::toEuler(void) const { return eul; } -Quaternion Quaternion::fromEuler(Vector<3> euler) { +Quaternion Quaternion::ConvertFromEuler(Vector<3> euler) { double esin[3], ecos[3]; for (int i = 0; i < 3; i++) { esin[i] = sin(euler[i]); @@ -209,11 +209,11 @@ Quaternion Quaternion::fromEuler(Vector<3> euler) { dcm[2][0] = esin[0] * esin[2] + ecos[0] * esin[1] * ecos[2]; dcm[2][1] = -esin[0] * ecos[2] + ecos[0] * esin[1] * esin[2]; dcm[2][2] = ecos[0] * ecos[1]; - return Quaternion::fromDCM(dcm); + return Quaternion::ConvertFromDcm(dcm); } -Vector<3> Quaternion::frame_conv(const Vector<3>& vector) const { - Quaternion conj = conjugate(); +Vector<3> Quaternion::FrameConversion(const Vector<3>& vector) const { + Quaternion conj = Conjugate(); Quaternion temp1 = conj * vector; Quaternion temp2 = temp1 * q_; Vector<3> ans; @@ -223,8 +223,8 @@ Vector<3> Quaternion::frame_conv(const Vector<3>& vector) const { return ans; } -Vector<3> Quaternion::frame_conv_inv(const Vector<3>& vector) const { - Quaternion conj = conjugate(); +Vector<3> Quaternion::InverseFrameConversion(const Vector<3>& vector) const { + Quaternion conj = Conjugate(); Quaternion temp1 = q_ * vector; Quaternion temp2 = temp1 * conj; Vector<3> ans; @@ -234,6 +234,6 @@ Vector<3> Quaternion::frame_conv_inv(const Vector<3>& vector) const { return ans; } -Vector<4> Quaternion::toVector() { return q_; } +Vector<4> Quaternion::ConvertToVector() { return q_; } } // namespace libra diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index d6902e977..10edd17e8 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -81,71 +81,71 @@ class Quaternion { inline operator const double*() const; /** - * @fn normalize + * @fn Normalize * @brief Normalize the quaternion * @return Normalized quaternion */ - Quaternion normalize(void); + Quaternion Normalize(void); /** - * @fn conjugate - * @brief Calculate conjugate quaternion + * @fn Conjugate + * @brief Calculate Conjugate quaternion * @return Conjugated quaternion */ - Quaternion conjugate(void) const; + Quaternion Conjugate(void) const; /** - * @fn toDCM + * @fn ConvertToDcm * @brief Convert quaternion to Direction Cosine Matrix * @return DCM */ - Matrix<3, 3> toDCM(void) const; + Matrix<3, 3> ConvertToDcm(void) const; /** - * @fn fromDCM + * @fn ConvertFromDcm * @brief Convert Direction Cosine Matrix to quaternion * @param [in] dcm: DCM * @return Quaternion */ - static Quaternion fromDCM(Matrix<3, 3> dcm); + static Quaternion ConvertFromDcm(Matrix<3, 3> dcm); /** - * @fn toEuler + * @fn ConvertToEuler * @brief Convert quaternion to 3-2-1 Euler angles * @return Euler angle (1, 2, 3 order) */ - Vector<3> toEuler(void) const; + Vector<3> ConvertToEuler(void) const; /** - * @fn fromEuler + * @fn ConvertFromEuler * @brief Convert Euler angle to quaternion * @param [in] euler: 3-2-1 Euler angle (1, 2, 3 order) * @return Quaternion */ - static Quaternion fromEuler(Vector<3> euler); + static Quaternion ConvertFromEuler(Vector<3> euler); /** - * @fn frame_conv + * @fn FrameConversion * @brief Frame conversion for the given target vector with the quaternion * @param [in] vector: Target vector * @return Converted vector */ - Vector<3> frame_conv(const Vector<3>& vector) const; + Vector<3> FrameConversion(const Vector<3>& vector) const; /** - * @fn frame_conv_inv + * @fn InverseFrameConversion * @brief Frame conversion for the given target vector with the inverse quaternion * @param [in] vector: Target vector * @return Converted vector */ - Vector<3> frame_conv_inv(const Vector<3>& vector) const; + Vector<3> InverseFrameConversion(const Vector<3>& vector) const; /** - * @fn toVector + * @fn ConvertToVector * @brief Convert quaternion to Vector<4> * @return Vector<4> */ - Vector<4> toVector(); + Vector<4> ConvertToVector(); private: Vector<4> q_; //!< Vector to store the element of quaternion diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index db8edf931..548a8c790 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -54,7 +54,7 @@ void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacec bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { Quaternion q_ecef_to_ltc = gs_position_geo_.GetQuaternionXcxfToLtc(); - Vector<3> sc_pos_ltc = q_ecef_to_ltc.frame_conv(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] + Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] normalize(sc_pos_ltc); Vector<3> dir_gs_to_zenith = Vector<3>(0); dir_gs_to_zenith[2] = 1; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index d57775b7d..7a014c6c4 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -57,7 +57,7 @@ void InitParameter::GetQuaternion(Quaternion& dst_quat) const { } } - dst_quat.normalize(); + dst_quat.Normalize(); } void InitParameter::Randomize() { @@ -203,11 +203,11 @@ void InitParameter::get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& m double rotation_angle_of_normal_unit_vec = InitParameter::Uniform_1d(0.0, libra::tau); Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) - Vector<3> rotation_axis = rotation_of_normal_unit_vec.frame_conv(normal_unit_vec); // Axis of mean vector rotation + Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation double rotation_angle_of_mean_vec = InitParameter::Normal_1d(0.0, sigma_or_max_[1]); Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) - Vector<3> ret_vec = rotation_of_mean_vec.frame_conv(mean_vec_dir); // Complete calculation of the direction + Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction ret_vec = InitParameter::Normal_1d(norm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 4047375b7..188a15381 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -106,7 +106,7 @@ void RelativeInformation::LogSetup(Logger& logger) { logger.AddLogList(this); } libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int target_sat_id, const int reference_sat_id) { // Observer SC Body frame(obs_sat) -> ECI frame(i) Quaternion q_reference_i2b = dynamics_database_.at(reference_sat_id)->GetAttitude().GetQuaternion_i2b(); - Quaternion q_reference_b2i = q_reference_i2b.conjugate(); + Quaternion q_reference_b2i = q_reference_i2b.Conjugate(); // ECI frame(i) -> Target SC body frame(main_sat) Quaternion q_target_i2b = dynamics_database_.at(target_sat_id)->GetAttitude().GetQuaternion_i2b(); @@ -122,7 +122,7 @@ libra::Vector<3> RelativeInformation::CalcRelativePosition_rtn_m(const int targe // RTN frame for the reference satellite libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternion_i2lvlh(); - libra::Vector<3> relative_pos_rtn = q_i2rtn.frame_conv(relative_pos_i); + libra::Vector<3> relative_pos_rtn = q_i2rtn.FrameConversion(relative_pos_i); return relative_pos_rtn; } @@ -142,7 +142,7 @@ libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int tar rot_vec_rtn_i /= r2_ref; libra::Vector<3> relative_vel_i = target_sat_vel_i - reference_sat_vel_i - cross(rot_vec_rtn_i, relative_pos_i); - libra::Vector<3> relative_vel_rtn = q_i2rtn.frame_conv(relative_vel_i); + libra::Vector<3> relative_vel_rtn = q_i2rtn.FrameConversion(relative_vel_i); return relative_vel_rtn; } From 16c2810ebb626c993f007c9c659671616ad615f3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 08:13:30 +0100 Subject: [PATCH 0678/1086] Fix typo --- src/environment/global/simulation_time.cpp | 6 +++--- src/environment/global/simulation_time.hpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/environment/global/simulation_time.cpp b/src/environment/global/simulation_time.cpp index 68a043974..24711d3c5 100644 --- a/src/environment/global/simulation_time.cpp +++ b/src/environment/global/simulation_time.cpp @@ -42,7 +42,7 @@ SimulationTime::SimulationTime(const double end_sec, const double step_sec, cons current_jd_ = start_jd_; current_sidereal_ = gstime(current_jd_); JdToDecyear(current_jd_, ¤t_decyear_); - ConvJDtoCalndarDay(current_jd_); + ConvJDtoCalendarDay(current_jd_); AssertTimeStepParams(); InitializeState(); SetParameters(); @@ -127,7 +127,7 @@ void SimulationTime::UpdateTime(void) { current_jd_ = start_jd_ + elapsed_time_sec_ / (60.0 * 60.0 * 24.0); current_sidereal_ = gstime(current_jd_); JdToDecyear(current_jd_, ¤t_decyear_); - ConvJDtoCalndarDay(current_jd_); + ConvJDtoCalendarDay(current_jd_); attitude_update_flag_ = false; if (double(attitude_update_counter_) * step_sec_ >= attitude_update_interval_sec_) { @@ -221,7 +221,7 @@ void SimulationTime::InitializeState() { } // wrapper function of invjday @ sgp4ext for interface adjustment -void SimulationTime::ConvJDtoCalndarDay(const double JD) { +void SimulationTime::ConvJDtoCalendarDay(const double JD) { int year, mon, day, hr, minute; double sec; invjday(JD, year, mon, day, hr, minute, sec); diff --git a/src/environment/global/simulation_time.hpp b/src/environment/global/simulation_time.hpp index 77a307207..3d6abe55c 100644 --- a/src/environment/global/simulation_time.hpp +++ b/src/environment/global/simulation_time.hpp @@ -314,10 +314,10 @@ class SimulationTime : public ILoggable { */ void AssertTimeStepParams(); /** - * @fn ConvJDtoCalndarDay + * @fn ConvJDtoCalendarDay * @brief Convert Julian date to UTC Calendar date * @note wrapper function of invjday @ sgp4ext for interface adjustment */ - void ConvJDtoCalndarDay(const double JD); + void ConvJDtoCalendarDay(const double JD); }; #endif // S2E_ENVIRONMENT_GLOBAL_SIMULATION_TIME_HPP_ From 5272a429df28a08e55feac1b91382638902028c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 14:06:30 +0100 Subject: [PATCH 0679/1086] Fix MACRO to const value --- src/dynamics/attitude/controlled_attitude.cpp | 5 +---- src/dynamics/attitude/controlled_attitude.hpp | 4 ++++ 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 497f38cf0..fa1cba923 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -5,11 +5,8 @@ #include "controlled_attitude.hpp" #include -#include #include -#define THRESHOLD_CA cos(30.0 / 180.0 * libra::pi) // FIXME - ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const libra::Quaternion quaternion_i2b, const libra::Vector<3> main_target_direction_b, const libra::Vector<3> sub_target_direction_b, const libra::Matrix<3, 3>& inertia_tensor_kgm2, @@ -49,7 +46,7 @@ void ControlledAttitude::Initialize(void) { normalize(sub_target_direction_b_); double tmp = inner_product(main_target_direction_b_, sub_target_direction_b_); tmp = std::abs(tmp); - if (tmp > THRESHOLD_CA) { + if (tmp > cos(kMinDirectionAngle_rad)) { std::cout << "sub target direction should separate from the main target direction. \n"; is_calc_enabled_ = false; return; diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 934bbad12..bd39a375f 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -7,6 +7,7 @@ #define S2E_DYNAMICS_ATTITUDE_CONTROLLED_ATTITUDE_HPP_ #include +#include #include #include "../orbit/orbit.hpp" @@ -105,6 +106,9 @@ class ControlledAttitude : public Attitude { libra::Quaternion previous_quaternion_i2b_; //!< Previous quaternion libra::Vector<3> previous_omega_b_rad_s_; //!< Previous angular velocity [rad/s] + const double kMinDirectionAngle_rad = 30.0 * libra::deg_to_rad; //!< Minimum angle b/w main and sub direction + // TODO Change with ini file + // Inputs const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information const Orbit* orbit_; //!< Orbit information From ffa9b6f7d3addb41ce6e911339480e9be09ce2cc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 14:10:14 +0100 Subject: [PATCH 0680/1086] Fix mu to gravity constant --- src/dynamics/orbit/initialize_orbit.cpp | 25 ++++++++++++------------- src/dynamics/orbit/initialize_orbit.hpp | 8 ++++---- 2 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index d6540fd24..569bb9004 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -13,7 +13,7 @@ #include "sgp4_orbit_propagation.hpp" Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string initialize_file, double step_width_s, double current_time_jd, - double mu_m3_s2, std::string section, RelativeInformation* relative_information) { + double gravity_constant_m3_s2, std::string section, RelativeInformation* relative_information) { auto conf = IniAccess(initialize_file); const char* section_ = section.c_str(); Orbit* orbit; @@ -28,12 +28,12 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // initialize RK4 orbit propagator Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, gravity_constant_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celestial_information, mu_m3_s2, step_width_s, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant_m3_s2, step_width_s, position_i_m, velocity_i_m_s); } else if (propagate_mode == "SGP4") { // Initialize SGP4 orbit propagator int wgs_setting = conf.ReadInt(section_, "wgs_setting"); @@ -58,11 +58,10 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string // the orbit of the reference sat is initialized, create temporary initial orbit of the reference sat int reference_spacecraft_id = conf.ReadInt(section_, "reference_satellite_id"); - orbit = new RelativeOrbit(celestial_information, mu_m3_s2, step_width_s, reference_spacecraft_id, init_relative_position_lvlh, + orbit = new RelativeOrbit(celestial_information, gravity_constant_m3_s2, step_width_s, reference_spacecraft_id, init_relative_position_lvlh, init_relative_velocity_lvlh, update_method, relative_dynamics_model_type, stm_model_type, relative_information); } else if (propagate_mode == "KEPLER") { // initialize orbit for Kepler propagation - double mu_m3_s2 = mu_m3_s2; OrbitalElements oe; // TODO: init_mode_kepler should be removed in the next major update if (initialize_mode == OrbitInitializeMode::kInertialPositionAndVelocity) { @@ -71,7 +70,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string conf.ReadVector<3>(section_, "initial_position_i_m", init_pos_m); Vector<3> init_vel_m_s; conf.ReadVector<3>(section_, "initial_velocity_i_m_s", init_vel_m_s); - oe = OrbitalElements(mu_m3_s2, current_time_jd, init_pos_m, init_vel_m_s); + oe = OrbitalElements(gravity_constant_m3_s2, current_time_jd, init_pos_m, init_vel_m_s); } else { // initialize with orbital elements double semi_major_axis_m = conf.ReadDouble(section_, "semi_major_axis_m"); @@ -82,32 +81,32 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string double epoch_jday = conf.ReadDouble(section_, "epoch_jday"); oe = OrbitalElements(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); } - KeplerOrbit kepler_orbit(mu_m3_s2, oe); + KeplerOrbit kepler_orbit(gravity_constant_m3_s2, oe); orbit = new KeplerOrbitPropagation(celestial_information, current_time_jd, kepler_orbit); } else if (propagate_mode == "ENCKE") { // initialize orbit for Encke's method Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, gravity_constant_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } double error_tolerance = conf.ReadDouble(section_, "error_tolerance"); - orbit = new EnckeOrbitPropagation(celestial_information, mu_m3_s2, step_width_s, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); + orbit = new EnckeOrbitPropagation(celestial_information, gravity_constant_m3_s2, step_width_s, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); } else { std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; Vector<3> position_i_m; Vector<3> velocity_i_m_s; - Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, mu_m3_s2); + Vector<6> pos_vel = InitializePosVel(initialize_file, current_time_jd, gravity_constant_m3_s2); for (size_t i = 0; i < 3; i++) { position_i_m[i] = pos_vel[i]; velocity_i_m_s[i] = pos_vel[i + 3]; } - orbit = new Rk4OrbitPropagation(celestial_information, mu_m3_s2, step_width_s, position_i_m, velocity_i_m_s); + orbit = new Rk4OrbitPropagation(celestial_information, gravity_constant_m3_s2, step_width_s, position_i_m, velocity_i_m_s); } orbit->SetIsCalcEnabled(conf.ReadEnable(section_, "calculation")); @@ -115,7 +114,7 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string return orbit; } -Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section) { +Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double gravity_constant_m3_s2, std::string section) { auto conf = IniAccess(initialize_file); const char* section_ = section.c_str(); Vector<3> position_i_m; @@ -131,7 +130,7 @@ Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double arg_perigee_rad = conf.ReadDouble(section_, "argument_of_perigee_rad"); double epoch_jday = conf.ReadDouble(section_, "epoch_jday"); OrbitalElements oe(epoch_jday, semi_major_axis_m, eccentricity, inclination_rad, raan_rad, arg_perigee_rad); - KeplerOrbit kepler_orbit(mu_m3_s2, oe); + KeplerOrbit kepler_orbit(gravity_constant_m3_s2, oe); kepler_orbit.CalcPosVel(current_time_jd); position_i_m = kepler_orbit.GetPosition_i_m(); diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index e41755506..b51fea8e9 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -19,21 +19,21 @@ class RelativeInformation; * @param [in] initialize_file: Path to initialize file * @param [in] step_width_s: Step width [sec] * @param [in] current_time_jd: Current Julian day [day] - * @param [in] mu_m3_s2: Gravity constant [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name * @param [in] relative_information: Relative information */ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string initialize_file, double step_width_s, double current_time_jd, - double mu_m3_s2, std::string section = "ORBIT", RelativeInformation* relative_information = (RelativeInformation*)nullptr); + double gravity_constant_m3_s2, std::string section = "ORBIT", RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** * @fn InitializePosVel * @brief Initialize position and velocity depends on initialize mode * @param [in] initialize_file: Path to initialize file * @param [in] current_time_jd: Current Julian day [day] - * @param [in] mu_m3_s2: Gravity constant [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant [m3/s2] * @param [in] section: Section name */ -Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double mu_m3_s2, std::string section = "ORBIT"); +Vector<6> InitializePosVel(std::string initialize_file, double current_time_jd, double gravity_constant_m3_s2, std::string section = "ORBIT"); #endif // S2E_DYNAMICS_ORBIT_INITIALIZE_ORBIT_HPP_ From 9a4a702d0daf4ec9c21d83b849d644569079f5b5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 14:25:04 +0100 Subject: [PATCH 0681/1086] Fix mu to gravity constant --- .../orbit/encke_orbit_propagation.cpp | 11 +++---- .../orbit/encke_orbit_propagation.hpp | 12 ++++---- src/dynamics/orbit/initialize_orbit.cpp | 3 +- src/dynamics/orbit/initialize_orbit.hpp | 3 +- src/dynamics/orbit/relative_orbit.cpp | 29 ++++++++++--------- src/dynamics/orbit/relative_orbit.hpp | 17 ++++++----- src/dynamics/orbit/rk4_orbit_propagation.cpp | 10 +++---- src/dynamics/orbit/rk4_orbit_propagation.hpp | 12 ++++---- 8 files changed, 52 insertions(+), 45 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 9a9590440..cdee38c8f 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -9,12 +9,12 @@ #include "../../library/orbit/orbital_elements.hpp" -EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, +EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double gravity_constant_m3_s2, const double propagation_step_s, const double current_time_jd, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s, const double error_tolerance) : Orbit(celestial_information), libra::ODE<6>(propagation_step_s), - mu_m3_s2_(mu_m3_s2), + gravity_constant_m3_s2_(gravity_constant_m3_s2), error_tolerance_(error_tolerance), propagation_step_s_(propagation_step_s) { propagation_time_s_ = 0.0; @@ -71,7 +71,8 @@ void EnckeOrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra:: double r_m = norm(reference_position_i_m_); double r_m3 = pow(r_m, 3.0); - difference_acc_i_m_s2 = -(mu_m3_s2_ / r_m3) * (q_func * spacecraft_position_i_m_ + difference_position_i_m_m) + spacecraft_acceleration_i_m_s2_; + difference_acc_i_m_s2 = + -(gravity_constant_m3_s2_ / r_m3) * (q_func * spacecraft_position_i_m_ + difference_position_i_m_m) + spacecraft_acceleration_i_m_s2_; rhs[0] = state[3]; rhs[1] = state[4]; @@ -89,8 +90,8 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> // reference orbit reference_position_i_m_ = reference_position_i_m; reference_velocity_i_m_s_ = reference_velocity_i_m_s; - OrbitalElements oe_ref(mu_m3_s2_, current_time_jd, reference_position_i_m, reference_velocity_i_m_s); - reference_kepler_orbit = KeplerOrbit(mu_m3_s2_, oe_ref); + OrbitalElements oe_ref(gravity_constant_m3_s2_, current_time_jd, reference_position_i_m, reference_velocity_i_m_s); + reference_kepler_orbit = KeplerOrbit(gravity_constant_m3_s2_, oe_ref); // difference orbit fill_up(difference_position_i_m_, 0.0); diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index f83421d17..671fb72f0 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -20,14 +20,14 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { * @fn EnckeOrbitPropagation * @brief Constructor * @param [in] celestial_information: Celestial information - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] propagation_step_s: Propagation step width [sec] * @param [in] current_time_jd: Current Julian day [day] * @param [in] position_i_m: Initial value of position in the inertial frame [m] * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] * @param [in] error_tolerance: Error tolerance threshold */ - EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double mu_m3_s2, const double propagation_step_s, + EnckeOrbitPropagation(const CelestialInformation* celestial_information, const double gravity_constant_m3_s2, const double propagation_step_s, const double current_time_jd, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s, const double error_tolerance); /** @@ -57,10 +57,10 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { private: // General - const double mu_m3_s2_; //!< Gravity constant of the center body [m3/s2] - const double error_tolerance_; //!< Error tolerance ratio - double propagation_step_s_; //!< Propagation step width for RK4 - double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 + const double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] + const double error_tolerance_; //!< Error tolerance ratio + double propagation_step_s_; //!< Propagation step width for RK4 + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 // reference orbit libra::Vector<3> reference_position_i_m_; //!< Reference orbit position in the inertial frame [m] diff --git a/src/dynamics/orbit/initialize_orbit.cpp b/src/dynamics/orbit/initialize_orbit.cpp index 569bb9004..b23748d8a 100644 --- a/src/dynamics/orbit/initialize_orbit.cpp +++ b/src/dynamics/orbit/initialize_orbit.cpp @@ -94,7 +94,8 @@ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string } double error_tolerance = conf.ReadDouble(section_, "error_tolerance"); - orbit = new EnckeOrbitPropagation(celestial_information, gravity_constant_m3_s2, step_width_s, current_time_jd, position_i_m, velocity_i_m_s, error_tolerance); + orbit = new EnckeOrbitPropagation(celestial_information, gravity_constant_m3_s2, step_width_s, current_time_jd, position_i_m, velocity_i_m_s, + error_tolerance); } else { std::cerr << "ERROR: orbit propagation mode: " << propagate_mode << " is not defined!" << std::endl; std::cerr << "The orbit mode is automatically set as RK4" << std::endl; diff --git a/src/dynamics/orbit/initialize_orbit.hpp b/src/dynamics/orbit/initialize_orbit.hpp index b51fea8e9..405966f2b 100644 --- a/src/dynamics/orbit/initialize_orbit.hpp +++ b/src/dynamics/orbit/initialize_orbit.hpp @@ -24,7 +24,8 @@ class RelativeInformation; * @param [in] relative_information: Relative information */ Orbit* InitOrbit(const CelestialInformation* celestial_information, std::string initialize_file, double step_width_s, double current_time_jd, - double gravity_constant_m3_s2, std::string section = "ORBIT", RelativeInformation* relative_information = (RelativeInformation*)nullptr); + double gravity_constant_m3_s2, std::string section = "ORBIT", + RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** * @fn InitializePosVel diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 73c19c145..dbfcade46 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -8,13 +8,13 @@ #include "rk4_orbit_propagation.hpp" -RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, - libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, +RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, double gravity_constant_m3_s2, double time_step_s, + int reference_spacecraft_id, libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* relative_information) : Orbit(celestial_information), libra::ODE<6>(time_step_s), - mu_m3_s2_(mu_m3_s2), + gravity_constant_m3_s2_(gravity_constant_m3_s2), reference_spacecraft_id_(reference_spacecraft_id), update_method_(update_method), relative_dynamics_model_type_(relative_dynamics_model_type), @@ -25,13 +25,13 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, propagation_time_s_ = 0.0; propagation_step_s_ = time_step_s; - InitializeState(relative_position_lvlh_m, relative_velocity_lvlh_m_s, mu_m3_s2); + InitializeState(relative_position_lvlh_m, relative_velocity_lvlh_m_s, gravity_constant_m3_s2); } RelativeOrbit::~RelativeOrbit() {} -void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, - double initial_time_s) { +void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, + double gravity_constant_m3_s2, double initial_time_s) { relative_position_lvlh_m_ = relative_position_lvlh_m; relative_velocity_lvlh_m_s_ = relative_velocity_lvlh_m_s; @@ -56,21 +56,23 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l if (update_method_ == RK4) { setup(initial_time_s, initial_state_); CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), - mu_m3_s2); + gravity_constant_m3_s2); } else // update_method_ == STM { - CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2, 0.0); + CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), gravity_constant_m3_s2, + 0.0); } TransformEciToEcef(); TransformEcefToGeodetic(); } -void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2) { +void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, + double gravity_constant_m3_s2) { switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, mu_m3_s2); + system_matrix_ = CalculateHillSystemMatrix(reference_sat_orbit_radius, gravity_constant_m3_s2); } default: { // NOT REACHED @@ -79,11 +81,11 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m } } -void RelativeOrbit::CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec) { +void RelativeOrbit::CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2, double elapsed_sec) { switch (stm_model_type) { case STMModel::HCW: { double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); - stm_ = CalculateHCWSTM(reference_sat_orbit_radius, mu_m3_s2, elapsed_sec); + stm_ = CalculateHCWSTM(reference_sat_orbit_radius, gravity_constant_m3_s2, elapsed_sec); } default: { // NOT REACHED @@ -138,7 +140,8 @@ void RelativeOrbit::PropagateRk4(double elapsed_sec) { void RelativeOrbit::PropagateStm(double elapsed_sec) { libra::Vector<6> current_state; - CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), mu_m3_s2_, elapsed_sec); + CalculateStm(stm_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), gravity_constant_m3_s2_, + elapsed_sec); current_state = stm_ * initial_state_; relative_position_lvlh_m_[0] = current_state[0]; diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 1f15aa4dd..b10ddce63 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -30,6 +30,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @brief Constructor * @param [in] celestial_information: Celestial information * @param [in] time_step_s: Time step [sec] + * @param [in] gravity_constant_m3_s2: Gravity constant [m3/s2] * @param [in] reference_spacecraft_id: Reference satellite ID * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite @@ -38,7 +39,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @param [in] stm_model_type: State transition matrix type * @param [in] relative_information: Relative information */ - RelativeOrbit(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, int reference_spacecraft_id, + RelativeOrbit(const CelestialInformation* celestial_information, double gravity_constant_m3_s2, double time_step_s, int reference_spacecraft_id, libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, STMModel stm_model_type, RelativeInformation* relative_information); /** @@ -67,7 +68,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); private: - double mu_m3_s2_; //!< Gravity constant of the center body [m3/s2] + double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] unsigned int reference_spacecraft_id_; //!< Reference satellite ID double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] double propagation_step_s_; //!< Step width for RK4 [sec] @@ -89,28 +90,28 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { * @brief Initialize state variables * @param [in] relative_position_lvlh_m: Initial value of relative position at the LVLH frame of reference satellite * @param [in] relative_velocity_lvlh_m_s: Initial value of relative velocity at the LVLH frame of reference satellite - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] initial_time_s: Initialize time [sec] */ - void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double mu_m3_s2, + void InitializeState(libra::Vector<3> relative_position_lvlh_m, libra::Vector<3> relative_velocity_lvlh_m_s, double gravity_constant_m3_s2, double initial_time_s = 0); /** * @fn CalculateSystemMatrix * @brief Calculate system matrix * @param [in] relative_dynamics_model_type: Relative dynamics model type * @param [in] reference_sat_orbit: Orbit information of reference satellite - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] */ - void CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2); + void CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2); /** * @fn CalculateStm * @brief Calculate State Transition Matrix * @param [in] stm_model_type: STM model type * @param [in] reference_sat_orbit: Orbit information of reference satellite - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] elapsed_sec: Elapsed time [sec] */ - void CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double mu_m3_s2, double elapsed_sec); + void CalculateStm(STMModel stm_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2, double elapsed_sec); /** * @fn PropagateRk4 * @brief Propagate relative orbit with RK4 diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index befe3f427..0f756945f 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -8,9 +8,9 @@ #include #include -Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, +Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double gravity_constant_m3_s2, double time_step_s, libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) - : Orbit(celestial_information), ODE<6>(time_step_s), mu_m3_s2(mu_m3_s2) { + : Orbit(celestial_information), ODE<6>(time_step_s), gravity_constant_m3_s2_(gravity_constant_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; propagation_time_s_ = 0.0; @@ -31,9 +31,9 @@ void Rk4OrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Ve rhs[0] = vx; rhs[1] = vy; rhs[2] = vz; - rhs[3] = spacecraft_acceleration_i_m_s2_[0] - mu_m3_s2 / r3 * x; - rhs[4] = spacecraft_acceleration_i_m_s2_[1] - mu_m3_s2 / r3 * y; - rhs[5] = spacecraft_acceleration_i_m_s2_[2] - mu_m3_s2 / r3 * z; + rhs[3] = spacecraft_acceleration_i_m_s2_[0] - gravity_constant_m3_s2_ / r3 * x; + rhs[4] = spacecraft_acceleration_i_m_s2_[1] - gravity_constant_m3_s2_ / r3 * y; + rhs[5] = spacecraft_acceleration_i_m_s2_[2] - gravity_constant_m3_s2_ / r3 * z; (void)t; } diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 989cb1209..6c745668d 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -21,14 +21,14 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { * @fn Rk4OrbitPropagation * @brief Constructor * @param [in] celestial_information: Celestial information - * @param [in] mu_m3_s2: Gravity constant [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant [m3/s2] * @param [in] time_step_s: Step width [sec] * @param [in] position_i_m: Initial value of position in the inertial frame [m] * @param [in] velocity_i_m_s: Initial value of velocity in the inertial frame [m/s] * @param [in] initial_time_s: Initial time [sec] */ - Rk4OrbitPropagation(const CelestialInformation* celestial_information, double mu_m3_s2, double time_step_s, libra::Vector<3> position_i_m, - libra::Vector<3> velocity_i_m_s, double initial_time_s = 0); + Rk4OrbitPropagation(const CelestialInformation* celestial_information, double gravity_constant_m3_s2, double time_step_s, + libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s = 0); /** * @fn ~Rk4OrbitPropagation * @brief Destructor @@ -55,9 +55,9 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { virtual void Propagate(double end_time_s, double current_time_jd); private: - double mu_m3_s2; //!< Gravity constant [m3/s2] - double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] - double propagation_step_s_; //!< Step width for RK4 [sec] + double gravity_constant_m3_s2_; //!< Gravity constant [m3/s2] + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] + double propagation_step_s_; //!< Step width for RK4 [sec] /** * @fn Initialize From f4d584e999d4a45b74d8af71f2e02aec177df5dc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 14:27:00 +0100 Subject: [PATCH 0682/1086] Fix mu to gravity constant --- src/disturbances/gravity_gradient.cpp | 6 +++--- src/disturbances/gravity_gradient.hpp | 6 +++--- src/disturbances/initialize_disturbances.cpp | 4 ++-- src/disturbances/initialize_disturbances.hpp | 4 ++-- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 479450d36..83a3be60d 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -13,8 +13,8 @@ GravityGradient::GravityGradient(const bool is_calculation_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calculation_enabled) {} -GravityGradient::GravityGradient(const double mu_m3_s2, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), mu_m3_s2_(mu_m3_s2) {} +GravityGradient::GravityGradient(const double gravity_constant_m3_s2, const bool is_calculation_enabled) + : SimpleDisturbance(is_calculation_enabled), gravity_constant_m3_s2_(gravity_constant_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor @@ -27,7 +27,7 @@ libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_p libra::Vector<3> u_b = earth_position_from_sc_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; - double coeff = 3.0 * mu_m3_s2_ / pow(r_norm_m, 3.0); + double coeff = 3.0 * gravity_constant_m3_s2_ / pow(r_norm_m, 3.0); torque_b_Nm_ = coeff * outer_product(u_b, inertia_tensor_b_kgm2 * u_b); return torque_b_Nm_; } diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index bb86857e2..11fbd7802 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -30,10 +30,10 @@ class GravityGradient : public SimpleDisturbance { /** * @fn GeoPotential * @brief Constructor - * @param [in] mu_m3_s2: Gravitational constant [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravitational constant [m3/s2] * @param [in] is_calculation_enabled: Calculation flag */ - GravityGradient(const double mu_m3_s2, const bool is_calculation_enabled = true); + GravityGradient(const double gravity_constant_m3_s2, const bool is_calculation_enabled = true); /** * @fn Update @@ -56,7 +56,7 @@ class GravityGradient : public SimpleDisturbance { virtual std::string GetLogValue() const; private: - double mu_m3_s2_; //!< Gravitational constant [m3/s2] + double gravity_constant_m3_s2_; //!< Gravitational constant [m3/s2] /** * @fn CalcTorque diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 98a560bff..249385f25 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -52,12 +52,12 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path) { return gg_disturbance; } -GravityGradient InitGravityGradient(const std::string initialize_file_path, const double mu_m3_s2) { +GravityGradient InitGravityGradient(const std::string initialize_file_path, const double gravity_constant_m3_s2) { auto conf = IniAccess(initialize_file_path); const char* section = "GRAVITY_GRADIENT"; const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); - GravityGradient gg_disturbance(mu_m3_s2, is_calc_enable); + GravityGradient gg_disturbance(gravity_constant_m3_s2, is_calc_enable); gg_disturbance.IsLogEnabled = conf.ReadEnable(section, LOG_LABEL); return gg_disturbance; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index 7692d42cb..e5fea9d90 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -43,9 +43,9 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path); * @fn InitGravityGradient * @brief Initialize GravityGradient class with earth gravitational constant * @param [in] initialize_file_path: Initialize file path - * @param [in] mu_m3_s2: Gravitational constant [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravitational constant [m3/s2] */ -GravityGradient InitGravityGradient(const std::string initialize_file_path, const double mu_m3_s2); +GravityGradient InitGravityGradient(const std::string initialize_file_path, const double gravity_constant_m3_s2); /** * @fn InitMagneticDisturbance From edd7ba5f733a7c5ba4ba1ab6419d0f6ebc982e2d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 14:28:51 +0100 Subject: [PATCH 0683/1086] Fix format --- src/dynamics/attitude/controlled_attitude.hpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index bd39a375f..1e7a5c96d 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -107,7 +107,7 @@ class ControlledAttitude : public Attitude { libra::Vector<3> previous_omega_b_rad_s_; //!< Previous angular velocity [rad/s] const double kMinDirectionAngle_rad = 30.0 * libra::deg_to_rad; //!< Minimum angle b/w main and sub direction - // TODO Change with ini file + // TODO Change with ini file // Inputs const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 6c745668d..66dfd51a3 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -56,8 +56,8 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { private: double gravity_constant_m3_s2_; //!< Gravity constant [m3/s2] - double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] - double propagation_step_s_; //!< Step width for RK4 [sec] + double propagation_time_s_; //!< Simulation current time for numerical integration by RK4 [sec] + double propagation_step_s_; //!< Step width for RK4 [sec] /** * @fn Initialize From 0d6c16044675f12bbbc9d6cbda1e6c4b5078efba Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:15:11 +0100 Subject: [PATCH 0684/1086] Move inline function --- .../math/ordinary_differential_equation.hpp | 12 ++++---- ...differential_equation_inline_functions.hpp | 30 ------------------- 2 files changed, 6 insertions(+), 36 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index d25f84943..6b5ed2eda 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -56,32 +56,32 @@ class ODE { * @fn step_width * @brief Return step width */ - inline double step_width() const; + inline double step_width() const { return step_width_; } /** * @fn x * @brief Return current independent variable */ - inline double x() const; + inline double x() const { return x_; } /** * @fn state * @brief Return current state vector */ - inline const Vector& state() const; + inline const Vector& state() const { return state_; } /** * @fn operator [] * @brief Return element of current state vector * @param [in] n: Target element number */ - inline double operator[](int n) const; + inline double operator[](int n) const { return state_[n]; } /** * @fn rhs * @brief Return const reference of differentiate state vector */ - inline const Vector& rhs() const; + inline const Vector& rhs() const { return rhs_; } /** * @fn operator ++ @@ -100,7 +100,7 @@ class ODE { * @fn state * @brief Return current state vector for inheriting class */ - inline libra::Vector& state(); + inline libra::Vector& state() { return state_; } private: double x_; //!< Latest value of independent variable diff --git a/src/library/math/ordinary_differential_equation_inline_functions.hpp b/src/library/math/ordinary_differential_equation_inline_functions.hpp index 8dca553b9..46b5171f8 100644 --- a/src/library/math/ordinary_differential_equation_inline_functions.hpp +++ b/src/library/math/ordinary_differential_equation_inline_functions.hpp @@ -11,36 +11,6 @@ namespace libra { template ODE::~ODE() {} -template -double ODE::step_width() const { - return step_width_; -} - -template -double ODE::x() const { - return x_; -} - -template -const Vector& ODE::state() const { - return state_; -} - -template -double ODE::operator[](int n) const { - return state_[n]; -} - -template -const Vector& ODE::rhs() const { - return rhs_; -} - -template -libra::Vector& ODE::state() { - return state_; -} - } // namespace libra #endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ From d7f61abcbc311992086c4ff2065a98de38345cc4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:15:37 +0100 Subject: [PATCH 0685/1086] Remove unnecessary file --- ...ry_differential_equation_inline_functions.hpp | 16 ---------------- 1 file changed, 16 deletions(-) delete mode 100644 src/library/math/ordinary_differential_equation_inline_functions.hpp diff --git a/src/library/math/ordinary_differential_equation_inline_functions.hpp b/src/library/math/ordinary_differential_equation_inline_functions.hpp deleted file mode 100644 index 46b5171f8..000000000 --- a/src/library/math/ordinary_differential_equation_inline_functions.hpp +++ /dev/null @@ -1,16 +0,0 @@ -/** - * @file ordinary_differential_equation_inline_functions.hpp - * @brief Class for Ordinary Difference Equation (inline functions) - */ - -#ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ -#define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ - -namespace libra { - -template -ODE::~ODE() {} - -} // namespace libra - -#endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_INLINE_FUNCTIONS_HPP_ From 56d58736ebbd83216223687f41e58bd5fe07171e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:17:42 +0100 Subject: [PATCH 0686/1086] Remove unnecessary file --- src/library/math/ordinary_differential_equation.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 6b5ed2eda..d9ca4ad18 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -27,7 +27,7 @@ class ODE { * @fn ~ODE * @brief Destructor */ - inline virtual ~ODE(); + inline virtual ~ODE() {} /** * @fn RHS @@ -111,7 +111,6 @@ class ODE { } // namespace libra -#include "./ordinary_differential_equation_inline_functions.hpp" #include "./ordinary_differential_equation_template_functions.hpp" #endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ From a19c729e9eccd063728ef6fa55db836e89462920 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:44:04 +0100 Subject: [PATCH 0687/1086] Fix private variables --- .../math/ordinary_differential_equation.hpp | 12 ++++++------ ..._differential_equation_template_functions.hpp | 16 ++++++++-------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index d9ca4ad18..ecfd1f459 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -62,7 +62,7 @@ class ODE { * @fn x * @brief Return current independent variable */ - inline double x() const { return x_; } + inline double x() const { return independent_variable_; } /** * @fn state @@ -81,7 +81,7 @@ class ODE { * @fn rhs * @brief Return const reference of differentiate state vector */ - inline const Vector& rhs() const { return rhs_; } + inline const Vector& rhs() const { return derivative_; } /** * @fn operator ++ @@ -103,10 +103,10 @@ class ODE { inline libra::Vector& state() { return state_; } private: - double x_; //!< Latest value of independent variable - Vector state_; //!< Latest state vector - Vector rhs_; //!< Latest differentiate of the state vector - double step_width_; //!< Step width + double independent_variable_; //!< Latest value of independent variable + Vector state_; //!< Latest state vector + Vector derivative_; //!< Latest differentiate of the state vector + double step_width_; //!< Step width }; } // namespace libra diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 289307537..840a392df 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -8,11 +8,11 @@ namespace libra { template -ODE::ODE(double step_width) : x_(0.0), state_(0.0), rhs_(0.0), step_width_(step_width) {} +ODE::ODE(double step_width) : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} template void ODE::setup(double init_x, const Vector& init_cond) { - x_ = init_x; + independent_variable_ = init_x; state_ = init_cond; } @@ -24,23 +24,23 @@ ODE& ODE::operator++() { template void ODE::Update() { - RHS(x_, state_, rhs_); // Current derivative calculation + RHS(independent_variable_, state_, derivative_); // Current derivative calculation // 4th order Runge-Kutta method - Vector k1(rhs_); + Vector k1(derivative_); k1 *= step_width_; Vector k2(state_.dim()); - RHS(x_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); + RHS(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); k2 *= step_width_; Vector k3(state_.dim()); - RHS(x_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); + RHS(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); k3 *= step_width_; Vector k4(state_.dim()); - RHS(x_ + step_width_, state_ + k3, k4); + RHS(independent_variable_ + step_width_, state_ + k3, k4); k4 *= step_width_; state_ += (1.0 / 6.0) * (k1 + 2.0 * (k2 + k3) + k4); // Update state vector - x_ += step_width_; // Update independent variable + independent_variable_ += step_width_; // Update independent variable } template From 5ba380dba53f7ea4b2f87bf4c0c1ae543c786492 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:47:52 +0100 Subject: [PATCH 0688/1086] Fix function arguments --- .../math/ordinary_differential_equation.hpp | 14 +++++++------- ...ry_differential_equation_template_functions.hpp | 10 +++++----- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index ecfd1f459..8895f9215 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -34,23 +34,23 @@ class ODE { * @brief Pure virtual function to define the difference equation * @param [in] x: Independent variable (e.g. time) * @param [in] state: State vector - * @param [out] rhs: Differentiated value of state vector + * @param [out] derivative: Differentiated value of state vector */ - virtual void RHS(double x, const Vector& state, Vector& rhs) = 0; + virtual void RHS(double x, const Vector& state, Vector& derivative) = 0; /** * @fn setup * @brief Initialize the state vector - * @param [in] init_x: Initial value of independent variable - * @param [in] init_cond: Initial condition of the state vector + * @param [in] initial_independent_variable: Initial value of independent variable + * @param [in] initial_state: Initial condition of the state vector */ - void setup(double init_x, const Vector& init_cond); + void setup(double initial_independent_variable, const Vector& initial_state); /** * @fn setStepWidth * @brief Initialize the state vector - * @param [in] new_step: Initial value of independent variable + * @param [in] step_width: Step width */ - void setStepWidth(double new_step); + void setStepWidth(double step_width); /** * @fn step_width diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 840a392df..6e83f5155 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -11,9 +11,9 @@ template ODE::ODE(double step_width) : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} template -void ODE::setup(double init_x, const Vector& init_cond) { - independent_variable_ = init_x; - state_ = init_cond; +void ODE::setup(double initial_independent_variable, const Vector& initial_state) { + independent_variable_ = initial_independent_variable; + state_ = initial_state; } template @@ -44,8 +44,8 @@ void ODE::Update() { } template -void ODE::setStepWidth(double new_step) { - step_width_ = new_step; +void ODE::setStepWidth(double step_width) { + step_width_ = step_width; } } // namespace libra From 8588c070604c575b9aed35a15b8e946e1e3d6769 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:48:41 +0100 Subject: [PATCH 0689/1086] Move to inline function --- src/library/math/ordinary_differential_equation.hpp | 2 +- .../ordinary_differential_equation_template_functions.hpp | 4 ---- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 8895f9215..c22cdf33a 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -50,7 +50,7 @@ class ODE { * @brief Initialize the state vector * @param [in] step_width: Step width */ - void setStepWidth(double step_width); + inline void setStepWidth(double step_width) { step_width_ = step_width; } /** * @fn step_width diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 6e83f5155..9d5959a62 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -43,10 +43,6 @@ void ODE::Update() { independent_variable_ += step_width_; // Update independent variable } -template -void ODE::setStepWidth(double step_width) { - step_width_ = step_width; -} } // namespace libra #endif // S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ From c76db7b8d01e11bcbba17a1a1c0df02f0514a6fc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:53:02 +0100 Subject: [PATCH 0690/1086] Fix public get functions name --- .../real/aocs/reaction_wheel_ode.cpp | 2 +- .../math/ordinary_differential_equation.hpp | 50 ++++++++++--------- 2 files changed, 27 insertions(+), 25 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 19efb3642..4633d2d2a 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -14,7 +14,7 @@ RwOde::RwOde(double step_width, double init_angular_velocity, double target_angu } double RwOde::getAngularVelocity(void) const { - double angular_velocity = this->state()[0]; + double angular_velocity = this->GetState()[0]; return angular_velocity; } diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index c22cdf33a..d2b7d0c54 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -38,6 +38,18 @@ class ODE { */ virtual void RHS(double x, const Vector& state, Vector& derivative) = 0; + /** + * @fn operator ++ + * @brief Update the state + */ + ODE& operator++(); + + /** + * @fn Update + * @brief Update the state + */ + void Update(); + /** * @fn setup * @brief Initialize the state vector @@ -45,6 +57,7 @@ class ODE { * @param [in] initial_state: Initial condition of the state vector */ void setup(double initial_independent_variable, const Vector& initial_state); + /** * @fn setStepWidth * @brief Initialize the state vector @@ -52,48 +65,37 @@ class ODE { */ inline void setStepWidth(double step_width) { step_width_ = step_width; } + // Getter /** - * @fn step_width + * @fn GetStepWidth * @brief Return step width */ - inline double step_width() const { return step_width_; } + inline double GetStepWidth() const { return step_width_; } /** - * @fn x + * @fn GetIndependentVariable * @brief Return current independent variable */ - inline double x() const { return independent_variable_; } + inline double GetIndependentVariable() const { return independent_variable_; } /** - * @fn state + * @fn GetState * @brief Return current state vector */ - inline const Vector& state() const { return state_; } - - /** - * @fn operator [] - * @brief Return element of current state vector - * @param [in] n: Target element number - */ - inline double operator[](int n) const { return state_[n]; } + inline const Vector& GetState() const { return state_; } /** - * @fn rhs + * @fn GetDerivative * @brief Return const reference of differentiate state vector */ - inline const Vector& rhs() const { return derivative_; } + inline const Vector& GetDerivative() const { return derivative_; } /** - * @fn operator ++ - * @brief Update the state - */ - ODE& operator++(); - - /** - * @fn Update - * @brief Update the state + * @fn operator [] + * @brief Return element of current state vector + * @param [in] n: Target element number */ - void Update(); + inline double operator[](int n) const { return state_[n]; } protected: /** From b7892f2e894e311d0ccb4132ae80c81093f99e62 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:55:42 +0100 Subject: [PATCH 0691/1086] Fix public set functions name --- src/components/real/aocs/reaction_wheel_ode.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 6 +++--- src/dynamics/orbit/relative_orbit.cpp | 6 +++--- src/dynamics/orbit/rk4_orbit_propagation.cpp | 6 +++--- src/library/math/ordinary_differential_equation.hpp | 8 ++++---- .../ordinary_differential_equation_template_functions.hpp | 2 +- 6 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 4633d2d2a..0b34c13c9 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -10,7 +10,7 @@ using namespace libra; RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, Vector<3> lag_coef) : ODE<1>(step_width), lag_coef_(lag_coef), kInitAngularVelocity_(init_angular_velocity), target_angular_velocity_(target_angular_velocity) { - this->setup(0.0, Vector<1>(init_angular_velocity)); + this->Setup(0.0, Vector<1>(init_angular_velocity)); } double RwOde::getAngularVelocity(void) const { diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 28687f38f..20704a52f 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -40,12 +40,12 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) reference_velocity_i_m_s_ = reference_kepler_orbit.GetVelocity_i_m_s(); // Propagate difference orbit - setStepWidth(propagation_step_s_); // Re-set propagation Δt + SetStepWidth(propagation_step_s_); // Re-set propagation Δt while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class propagation_time_s_ += propagation_step_s_; } - setStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt + SetStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt Update(); propagation_time_s_ = end_time_s; @@ -98,7 +98,7 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> fill_up(difference_velocity_i_m_s_, 0.0); libra::Vector<6> zero(0.0f); - setup(0.0, zero); + Setup(0.0, zero); UpdateSatOrbit(); } diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 2da572168..0969d42ee 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -54,7 +54,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l initial_state_[5] = relative_velocity_lvlh_m_s[2]; if (update_method_ == RK4) { - setup(initial_time_s, initial_state_); + Setup(initial_time_s, initial_state_); CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), gravity_constant_m3_s2); } else // update_method_ == STM @@ -121,12 +121,12 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { } void RelativeOrbit::PropagateRk4(double elapsed_sec) { - setStepWidth(propagation_step_s_); // Re-set propagation dt + SetStepWidth(propagation_step_s_); // Re-set propagation dt while (elapsed_sec - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class propagation_time_s_ += propagation_step_s_; } - setStepWidth(elapsed_sec - propagation_time_s_); // Adjust the last propagation dt + SetStepWidth(elapsed_sec - propagation_time_s_); // Adjust the last propagation dt Update(); propagation_time_s_ = elapsed_sec; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 8b96bb846..cb84f33c9 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -47,7 +47,7 @@ void Rk4OrbitPropagation::Initialize(libra::Vector<3> position_i_m, libra::Vecto init_state[3] = velocity_i_m_s[0]; init_state[4] = velocity_i_m_s[1]; init_state[5] = velocity_i_m_s[2]; - setup(initial_time_s, init_state); + Setup(initial_time_s, init_state); // initialize spacecraft_acceleration_i_m_s2_ *= 0; @@ -67,12 +67,12 @@ void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { if (!is_calc_enabled_) return; - setStepWidth(propagation_step_s_); // Re-set propagation Δt + SetStepWidth(propagation_step_s_); // Re-set propagation Δt while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { Update(); // Propagation methods of the ODE class propagation_time_s_ += propagation_step_s_; } - setStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt + SetStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt Update(); propagation_time_s_ = end_time_s; diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index d2b7d0c54..1e22291d4 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -51,19 +51,19 @@ class ODE { void Update(); /** - * @fn setup + * @fn Setup * @brief Initialize the state vector * @param [in] initial_independent_variable: Initial value of independent variable * @param [in] initial_state: Initial condition of the state vector */ - void setup(double initial_independent_variable, const Vector& initial_state); + void Setup(const double initial_independent_variable, const Vector& initial_state); /** - * @fn setStepWidth + * @fn SetStepWidth * @brief Initialize the state vector * @param [in] step_width: Step width */ - inline void setStepWidth(double step_width) { step_width_ = step_width; } + inline void SetStepWidth(const double step_width) { step_width_ = step_width; } // Getter /** diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 9d5959a62..2ec99156c 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -11,7 +11,7 @@ template ODE::ODE(double step_width) : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} template -void ODE::setup(double initial_independent_variable, const Vector& initial_state) { +void ODE::Setup(double initial_independent_variable, const Vector& initial_state) { independent_variable_ = initial_independent_variable; state_ = initial_state; } From f5e34201f03acde7ee64d6132640b4310681ace4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 15:57:26 +0100 Subject: [PATCH 0692/1086] Fix protected get functions name --- src/components/real/aocs/reaction_wheel_ode.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 12 ++++++------ src/dynamics/orbit/relative_orbit.cpp | 12 ++++++------ src/dynamics/orbit/rk4_orbit_propagation.cpp | 12 ++++++------ src/library/math/ordinary_differential_equation.hpp | 4 ++-- 5 files changed, 21 insertions(+), 21 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 0b34c13c9..df9e46da4 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -36,7 +36,7 @@ void RwOde::RHS(double x, const Vector<1> &state, Vector<1> &rhs) { // lag_coef_[1] * (target_angular_velocity_ - this->state()[0]) + // lag_coef_[0]; // First-order-lag - rhs[0] = (target_angular_velocity_ - this->state()[0]) / (lag_coef_[0]); + rhs[0] = (target_angular_velocity_ - this->GetState()[0]) / (lag_coef_[0]); // Only target // rhs[0] = (target_angular_velocity_); } diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 20704a52f..c46d96c5c 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -49,12 +49,12 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) Update(); propagation_time_s_ = end_time_s; - difference_position_i_m_[0] = state()[0]; - difference_position_i_m_[1] = state()[1]; - difference_position_i_m_[2] = state()[2]; - difference_velocity_i_m_s_[0] = state()[3]; - difference_velocity_i_m_s_[1] = state()[4]; - difference_velocity_i_m_s_[2] = state()[5]; + difference_position_i_m_[0] = GetState()[0]; + difference_position_i_m_[1] = GetState()[1]; + difference_position_i_m_[2] = GetState()[2]; + difference_velocity_i_m_s_[0] = GetState()[3]; + difference_velocity_i_m_s_[1] = GetState()[4]; + difference_velocity_i_m_s_[2] = GetState()[5]; UpdateSatOrbit(); } diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 0969d42ee..08a7161bb 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -130,12 +130,12 @@ void RelativeOrbit::PropagateRk4(double elapsed_sec) { Update(); propagation_time_s_ = elapsed_sec; - relative_position_lvlh_m_[0] = state()[0]; - relative_position_lvlh_m_[1] = state()[1]; - relative_position_lvlh_m_[2] = state()[2]; - relative_velocity_lvlh_m_s_[0] = state()[3]; - relative_velocity_lvlh_m_s_[1] = state()[4]; - relative_velocity_lvlh_m_s_[2] = state()[5]; + relative_position_lvlh_m_[0] = GetState()[0]; + relative_position_lvlh_m_[1] = GetState()[1]; + relative_position_lvlh_m_[2] = GetState()[2]; + relative_velocity_lvlh_m_s_[0] = GetState()[3]; + relative_velocity_lvlh_m_s_[1] = GetState()[4]; + relative_velocity_lvlh_m_s_[2] = GetState()[5]; } void RelativeOrbit::PropagateStm(double elapsed_sec) { diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index cb84f33c9..66a92a80a 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -76,12 +76,12 @@ void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { Update(); propagation_time_s_ = end_time_s; - spacecraft_position_i_m_[0] = state()[0]; - spacecraft_position_i_m_[1] = state()[1]; - spacecraft_position_i_m_[2] = state()[2]; - spacecraft_velocity_i_m_s_[0] = state()[3]; - spacecraft_velocity_i_m_s_[1] = state()[4]; - spacecraft_velocity_i_m_s_[2] = state()[5]; + spacecraft_position_i_m_[0] = GetState()[0]; + spacecraft_position_i_m_[1] = GetState()[1]; + spacecraft_position_i_m_[2] = GetState()[2]; + spacecraft_velocity_i_m_s_[0] = GetState()[3]; + spacecraft_velocity_i_m_s_[1] = GetState()[4]; + spacecraft_velocity_i_m_s_[2] = GetState()[5]; TransformEciToEcef(); TransformEcefToGeodetic(); diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 1e22291d4..4cdea66ec 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -99,10 +99,10 @@ class ODE { protected: /** - * @fn state + * @fn GetState * @brief Return current state vector for inheriting class */ - inline libra::Vector& state() { return state_; } + inline libra::Vector& GetState() { return state_; } private: double independent_variable_; //!< Latest value of independent variable From 5faa8cef9e3e531fce44cd607f4f83a0ddc13ee3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:02:12 +0100 Subject: [PATCH 0693/1086] Fix public virtual function --- src/components/real/aocs/reaction_wheel_ode.cpp | 2 +- src/components/real/aocs/reaction_wheel_ode.hpp | 4 ++-- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/relative_orbit.cpp | 2 +- src/dynamics/orbit/relative_orbit.hpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 4 ++-- src/library/math/ordinary_differential_equation.hpp | 6 +++--- .../ordinary_differential_equation_template_functions.hpp | 8 ++++---- src/library/randomization/random_walk.hpp | 4 ++-- .../randomization/random_walk_template_functions.hpp | 2 +- 12 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index df9e46da4..7d40ef680 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -18,7 +18,7 @@ double RwOde::getAngularVelocity(void) const { return angular_velocity; } -void RwOde::RHS(double x, const Vector<1> &state, Vector<1> &rhs) { +void RwOde::DerivativeFunction(double x, const Vector<1> &state, Vector<1> &rhs) { // FIXME: fix this function UNUSED(x); UNUSED(state); diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 510a794b8..f48b2ac4c 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -27,13 +27,13 @@ class RwOde : public libra::ODE<1> { RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, libra::Vector<3> lag_coef); /** - * @fn RHS + * @fn DerivativeFunction * @brief Definition of the difference equation (Override function of ODE class) * @param [in] x: Independent variable (e.g. time) * @param [in] state: State vector * @param [out] rhs: Differentiated value of state vector */ - void RHS(double x, const libra::Vector<1>& state, libra::Vector<1>& rhs) override; + void DerivativeFunction(double x, const libra::Vector<1>& state, libra::Vector<1>& rhs) override; /** * @fn getAngularVelocity diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index c46d96c5c..1cce1563d 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -60,7 +60,7 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) } // Functions for ODE -void EnckeOrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { +void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { UNUSED(t); libra::Vector<3> difference_position_i_m_m, difference_acc_i_m_s2; for (int i = 0; i < 3; i++) { diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index 671fb72f0..b966a571e 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -47,13 +47,13 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { // Override ODE /** - * @fn RHS + * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation * @param [in] t: Time as independent variable * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); + virtual void DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); private: // General diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 08a7161bb..e766ef732 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -152,7 +152,7 @@ void RelativeOrbit::PropagateStm(double elapsed_sec) { relative_velocity_lvlh_m_s_[2] = current_state[5]; } -void RelativeOrbit::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) // only for RK4 relative dynamics propagation +void RelativeOrbit::DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) // only for RK4 relative dynamics propagation { rhs = system_matrix_ * state; (void)t; diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 9c96491cb..506507ac2 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -59,13 +59,13 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { // Override ODE /** - * @fn RHS + * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation * @param [in] t: Time as independent variable * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const Vector<6>& state, Vector<6>& rhs); + virtual void DerivativeFunction(double t, const Vector<6>& state, Vector<6>& rhs); private: double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 66a92a80a..64911b715 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -22,7 +22,7 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_i Rk4OrbitPropagation::~Rk4OrbitPropagation() {} -void Rk4OrbitPropagation::RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { +void Rk4OrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { double x = state[0], y = state[1], z = state[2]; double vx = state[3], vy = state[4], vz = state[5]; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index 66dfd51a3..fcf8b731e 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -37,13 +37,13 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { // Override ODE /** - * @fn RHS + * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation * @param [in] t: Time as independent variable * @param [in] state: Position and velocity as state vector * @param [out] rhs: Output of the function */ - virtual void RHS(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); + virtual void DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs); // Override Orbit /** diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 4cdea66ec..023d19d87 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -30,13 +30,13 @@ class ODE { inline virtual ~ODE() {} /** - * @fn RHS + * @fn DerivativeFunction * @brief Pure virtual function to define the difference equation - * @param [in] x: Independent variable (e.g. time) + * @param [in] independent_variable: Independent variable (e.g. time) * @param [in] state: State vector * @param [out] derivative: Differentiated value of state vector */ - virtual void RHS(double x, const Vector& state, Vector& derivative) = 0; + virtual void DerivativeFunction(double independent_variable, const Vector& state, Vector& derivative) = 0; /** * @fn operator ++ diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 2ec99156c..16d058e4e 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -24,19 +24,19 @@ ODE& ODE::operator++() { template void ODE::Update() { - RHS(independent_variable_, state_, derivative_); // Current derivative calculation + DerivativeFunction(independent_variable_, state_, derivative_); // Current derivative calculation // 4th order Runge-Kutta method Vector k1(derivative_); k1 *= step_width_; Vector k2(state_.dim()); - RHS(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); + DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); k2 *= step_width_; Vector k3(state_.dim()); - RHS(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); + DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); k3 *= step_width_; Vector k4(state_.dim()); - RHS(independent_variable_ + step_width_, state_ + k3, k4); + DerivativeFunction(independent_variable_ + step_width_, state_ + k3, k4); k4 *= step_width_; state_ += (1.0 / 6.0) * (k1 + 2.0 * (k2 + k3) + k4); // Update state vector diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index 0f6fcc22c..3472c4060 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -27,13 +27,13 @@ class RandomWalk : public libra::ODE { RandomWalk(double step_width_s, const libra::Vector& standard_deviation, const libra::Vector& limit); /** - * @fn RHS + * @fn DerivativeFunction * @brief Override function of ODE to define the difference equation * @param [in] x: Independent variable (e.g. time) * @param [in] state: State vector * @param [out] rhs: Differentiated value of state vector */ - virtual void RHS(double x, const libra::Vector& state, libra::Vector& rhs); + virtual void DerivativeFunction(double x, const libra::Vector& state, libra::Vector& rhs); private: libra::Vector limit_; //!< Limit of random walk diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index fdab6dd72..27ea0a149 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -19,7 +19,7 @@ RandomWalk::RandomWalk(double step_width_s, const libra::Vector& standard_ } template -void RandomWalk::RHS(double x, const libra::Vector& state, libra::Vector& rhs) { +void RandomWalk::DerivativeFunction(double x, const libra::Vector& state, libra::Vector& rhs) { UNUSED(x); // TODO: consider the x is really need for this function for (size_t i = 0; i < N; ++i) { From 466f97539824b388c25beb1bc668028559372a65 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:04:24 +0100 Subject: [PATCH 0694/1086] Fix comments --- src/library/math/ordinary_differential_equation.hpp | 4 ++-- .../ordinary_differential_equation_template_functions.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 023d19d87..18f9fb179 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -1,6 +1,6 @@ /** * @file ordinary_differential_equation.hpp - * @brief Class for Ordinary Difference Equation + * @brief Class for Ordinary Differential Equation */ #ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_HPP_ @@ -12,7 +12,7 @@ namespace libra { /** * @class ODE - * @brief Class for Ordinary Difference Equation + * @brief Class for Ordinary Differential Equation */ template class ODE { diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 16d058e4e..2fc1f4407 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -1,6 +1,6 @@ /** * @file ordinary_differential_equation_template_functions.hpp - * @brief Class for Ordinary Difference Equation (template functions) + * @brief Class for Ordinary Differential Equation (template functions) */ #ifndef S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ #define S2E_LIBRARY_MATH_ORDINARY_DIFFERENTIA_EQUATION_TEMPLATE_FUNCTIONS_HPP_ From e3db92745a5d2833c3e2a9b7e27061c5dd2ed705 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:05:02 +0100 Subject: [PATCH 0695/1086] Fix ODE class name --- src/components/real/aocs/reaction_wheel.cpp | 2 +- src/components/real/aocs/reaction_wheel.hpp | 2 +- src/components/real/aocs/reaction_wheel_ode.cpp | 5 ++++- src/components/real/aocs/reaction_wheel_ode.hpp | 6 +++--- src/dynamics/orbit/encke_orbit_propagation.cpp | 6 +++--- src/dynamics/orbit/encke_orbit_propagation.hpp | 4 ++-- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/orbit/relative_orbit.hpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.cpp | 4 ++-- src/dynamics/orbit/rk4_orbit_propagation.hpp | 4 ++-- .../math/ordinary_differential_equation.hpp | 14 +++++++------- ...ry_differential_equation_template_functions.hpp | 9 +++++---- src/library/randomization/random_walk.hpp | 4 ++-- .../random_walk_template_functions.hpp | 2 +- 14 files changed, 37 insertions(+), 33 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 77582176f..b0bbb2013 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -134,7 +134,7 @@ libra::Vector<3> RWModel::CalcTorque() { delay_buffer_accl_.push_back(target_accl_); delay_buffer_accl_.erase(delay_buffer_accl_.begin()); } - // Calc RW ODE + // Calc RW OrdinaryDifferentialEquation int itr_num = (int)ceil(dt_main_routine_ / step_width_); for (int i = 0; i < itr_num; i++) { ++ode_angular_velocity_; // propagate() diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index b15231576..5aa1000af 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -217,7 +217,7 @@ class RWModel : public ComponentBase, public ILoggable { libra::Vector<3> output_torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] libra::Vector<3> angular_momentum_b_{0.0}; //!< Angular momentum of RW [Nms] - RwOde ode_angular_velocity_; //!< Reaction Wheel ODE + RwOde ode_angular_velocity_; //!< Reaction Wheel OrdinaryDifferentialEquation RWJitter rw_jitter_; //!< RW jitter bool is_calculated_jitter_ = false; //!< Flag for calculation of jitter bool is_logged_jitter_ = false; //!< Flag for log output of jitter diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 7d40ef680..5b157048f 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -9,7 +9,10 @@ using namespace libra; RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, Vector<3> lag_coef) - : ODE<1>(step_width), lag_coef_(lag_coef), kInitAngularVelocity_(init_angular_velocity), target_angular_velocity_(target_angular_velocity) { + : OrdinaryDifferentialEquation<1>(step_width), + lag_coef_(lag_coef), + kInitAngularVelocity_(init_angular_velocity), + target_angular_velocity_(target_angular_velocity) { this->Setup(0.0, Vector<1>(init_angular_velocity)); } diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index f48b2ac4c..776c5c755 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -14,12 +14,12 @@ * @file RwOde * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -class RwOde : public libra::ODE<1> { +class RwOde : public libra::OrdinaryDifferentialEquation<1> { public: /** * @fn RwOde * @brief Constructor - * @param [in] step_width: Step width for ODE calculation + * @param [in] step_width: Step width for OrdinaryDifferentialEquation calculation * @param [in] init_angular_velocity: Initial angular velocity [rad/s] * @param [in] target_angular_velocity: Target angular velocity [rad/s] * @param [in] lag_coef: coefficients for first order lag @@ -28,7 +28,7 @@ class RwOde : public libra::ODE<1> { /** * @fn DerivativeFunction - * @brief Definition of the difference equation (Override function of ODE class) + * @brief Definition of the difference equation (Override function of OrdinaryDifferentialEquation class) * @param [in] x: Independent variable (e.g. time) * @param [in] state: State vector * @param [out] rhs: Differentiated value of state vector diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 1cce1563d..24dc50c6f 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -13,7 +13,7 @@ EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celesti const double propagation_step_s, const double current_time_jd, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s, const double error_tolerance) : Orbit(celestial_information), - libra::ODE<6>(propagation_step_s), + libra::OrdinaryDifferentialEquation<6>(propagation_step_s), gravity_constant_m3_s2_(gravity_constant_m3_s2), error_tolerance_(error_tolerance), propagation_step_s_(propagation_step_s) { @@ -42,7 +42,7 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) // Propagate difference orbit SetStepWidth(propagation_step_s_); // Re-set propagation Δt while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { - Update(); // Propagation methods of the ODE class + Update(); // Propagation methods of the OrdinaryDifferentialEquation class propagation_time_s_ += propagation_step_s_; } SetStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt @@ -59,7 +59,7 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) UpdateSatOrbit(); } -// Functions for ODE +// Functions for OrdinaryDifferentialEquation void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& state, libra::Vector<6>& rhs) { UNUSED(t); libra::Vector<3> difference_position_i_m_m, difference_acc_i_m_s2; diff --git a/src/dynamics/orbit/encke_orbit_propagation.hpp b/src/dynamics/orbit/encke_orbit_propagation.hpp index b966a571e..03d42f696 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.hpp +++ b/src/dynamics/orbit/encke_orbit_propagation.hpp @@ -14,7 +14,7 @@ * @class EnckeOrbitPropagation * @brief Class to propagate spacecraft orbit with Encke's method */ -class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { +class EnckeOrbitPropagation : public Orbit, public libra::OrdinaryDifferentialEquation<6> { public: /** * @fn EnckeOrbitPropagation @@ -45,7 +45,7 @@ class EnckeOrbitPropagation : public Orbit, public libra::ODE<6> { */ virtual void Propagate(const double end_time_s, const double current_time_jd); - // Override ODE + // Override OrdinaryDifferentialEquation /** * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index e766ef732..23c95226f 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -13,7 +13,7 @@ RelativeOrbit::RelativeOrbit(const CelestialInformation* celestial_information, RelativeOrbitUpdateMethod update_method, RelativeOrbitModel relative_dynamics_model_type, StmModel stm_model_type, RelativeInformation* relative_information) : Orbit(celestial_information), - libra::ODE<6>(time_step_s), + libra::OrdinaryDifferentialEquation<6>(time_step_s), gravity_constant_m3_s2_(gravity_constant_m3_s2), reference_spacecraft_id_(reference_spacecraft_id), update_method_(update_method), @@ -123,7 +123,7 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { void RelativeOrbit::PropagateRk4(double elapsed_sec) { SetStepWidth(propagation_step_s_); // Re-set propagation dt while (elapsed_sec - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { - Update(); // Propagation methods of the ODE class + Update(); // Propagation methods of the OrdinaryDifferentialEquation class propagation_time_s_ += propagation_step_s_; } SetStepWidth(elapsed_sec - propagation_time_s_); // Adjust the last propagation dt diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 506507ac2..568064a27 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -17,7 +17,7 @@ * @class RelativeOrbit * @brief Class to propagate relative orbit */ -class RelativeOrbit : public Orbit, public libra::ODE<6> { +class RelativeOrbit : public Orbit, public libra::OrdinaryDifferentialEquation<6> { public: /** * @enum RelativeOrbitUpdateMethod @@ -57,7 +57,7 @@ class RelativeOrbit : public Orbit, public libra::ODE<6> { */ virtual void Propagate(double end_time_s, double current_time_jd); - // Override ODE + // Override OrdinaryDifferentialEquation /** * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 64911b715..545e6e7d5 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -10,7 +10,7 @@ Rk4OrbitPropagation::Rk4OrbitPropagation(const CelestialInformation* celestial_information, double gravity_constant_m3_s2, double time_step_s, libra::Vector<3> position_i_m, libra::Vector<3> velocity_i_m_s, double initial_time_s) - : Orbit(celestial_information), ODE<6>(time_step_s), gravity_constant_m3_s2_(gravity_constant_m3_s2) { + : Orbit(celestial_information), OrdinaryDifferentialEquation<6>(time_step_s), gravity_constant_m3_s2_(gravity_constant_m3_s2) { propagate_mode_ = OrbitPropagateMode::kRk4; propagation_time_s_ = 0.0; @@ -69,7 +69,7 @@ void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { SetStepWidth(propagation_step_s_); // Re-set propagation Δt while (end_time_s - propagation_time_s_ - propagation_step_s_ > 1.0e-6) { - Update(); // Propagation methods of the ODE class + Update(); // Propagation methods of the OrdinaryDifferentialEquation class propagation_time_s_ += propagation_step_s_; } SetStepWidth(end_time_s - propagation_time_s_); // Adjust the last propagation Δt diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index fcf8b731e..fb363146e 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -15,7 +15,7 @@ * @class Rk4OrbitPropagation * @brief Class to propagate spacecraft orbit with Runge-Kutta-4 method */ -class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { +class Rk4OrbitPropagation : public Orbit, public libra::OrdinaryDifferentialEquation<6> { public: /** * @fn Rk4OrbitPropagation @@ -35,7 +35,7 @@ class Rk4OrbitPropagation : public Orbit, public libra::ODE<6> { */ ~Rk4OrbitPropagation(); - // Override ODE + // Override OrdinaryDifferentialEquation /** * @fn DerivativeFunction * @brief Right Hand Side of ordinary difference equation diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 18f9fb179..4072ae778 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -11,23 +11,23 @@ namespace libra { /** - * @class ODE + * @class OrdinaryDifferentialEquation * @brief Class for Ordinary Differential Equation */ template -class ODE { +class OrdinaryDifferentialEquation { public: /** - * @fn ODE + * @fn OrdinaryDifferentialEquation * @brief Constructor * @param [in] step_width: Step width */ - ODE(double step_width); + OrdinaryDifferentialEquation(double step_width); /** - * @fn ~ODE + * @fn ~OrdinaryDifferentialEquation * @brief Destructor */ - inline virtual ~ODE() {} + inline virtual ~OrdinaryDifferentialEquation() {} /** * @fn DerivativeFunction @@ -42,7 +42,7 @@ class ODE { * @fn operator ++ * @brief Update the state */ - ODE& operator++(); + OrdinaryDifferentialEquation& operator++(); /** * @fn Update diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 2fc1f4407..ebeac1cab 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -8,22 +8,23 @@ namespace libra { template -ODE::ODE(double step_width) : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} +OrdinaryDifferentialEquation::OrdinaryDifferentialEquation(double step_width) + : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} template -void ODE::Setup(double initial_independent_variable, const Vector& initial_state) { +void OrdinaryDifferentialEquation::Setup(double initial_independent_variable, const Vector& initial_state) { independent_variable_ = initial_independent_variable; state_ = initial_state; } template -ODE& ODE::operator++() { +OrdinaryDifferentialEquation& OrdinaryDifferentialEquation::operator++() { Update(); return *this; } template -void ODE::Update() { +void OrdinaryDifferentialEquation::Update() { DerivativeFunction(independent_variable_, state_, derivative_); // Current derivative calculation // 4th order Runge-Kutta method diff --git a/src/library/randomization/random_walk.hpp b/src/library/randomization/random_walk.hpp index 3472c4060..306888d4b 100644 --- a/src/library/randomization/random_walk.hpp +++ b/src/library/randomization/random_walk.hpp @@ -15,7 +15,7 @@ * @brief Class to calculate random wark value */ template -class RandomWalk : public libra::ODE { +class RandomWalk : public libra::OrdinaryDifferentialEquation { public: /** * @fn RandomWalk @@ -28,7 +28,7 @@ class RandomWalk : public libra::ODE { /** * @fn DerivativeFunction - * @brief Override function of ODE to define the difference equation + * @brief Override function of OrdinaryDifferentialEquation to define the difference equation * @param [in] x: Independent variable (e.g. time) * @param [in] state: State vector * @param [out] rhs: Differentiated value of state vector diff --git a/src/library/randomization/random_walk_template_functions.hpp b/src/library/randomization/random_walk_template_functions.hpp index 27ea0a149..3221d7228 100644 --- a/src/library/randomization/random_walk_template_functions.hpp +++ b/src/library/randomization/random_walk_template_functions.hpp @@ -11,7 +11,7 @@ template RandomWalk::RandomWalk(double step_width_s, const libra::Vector& standard_deviation, const libra::Vector& limit) - : libra::ODE(step_width_s), limit_(limit) { + : libra::OrdinaryDifferentialEquation(step_width_s), limit_(limit) { // Set standard deviation for (size_t i = 0; i < N; ++i) { normal_randomizer_[i].SetParameters(0.0, standard_deviation[i], global_randomization.MakeSeed()); From 525418fd3ca53560cb8e92cefe7f720a0c3b1ced Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:10:07 +0100 Subject: [PATCH 0696/1086] Fix private variables --- src/library/math/quaternion.cpp | 58 +++++++++---------- src/library/math/quaternion.hpp | 2 +- .../math/quaternion_inline_functions.hpp | 18 +++--- 3 files changed, 39 insertions(+), 39 deletions(-) diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index c8af5c26c..1129decb7 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -13,12 +13,12 @@ namespace libra { Quaternion::Quaternion(const Vector<3>& rotation_axis, double rotation_angle_rad) { rotation_angle_rad *= 0.5; - q_[3] = cos(rotation_angle_rad); + quaternion_[3] = cos(rotation_angle_rad); // Vector<3> norm = normalize(rotation_axis); - // for(size_t i=0; i<3; ++i){ q_[i] = norm[i]*sin(rotation_angle_rad); } + // for(size_t i=0; i<3; ++i){ quaternion_[i] = norm[i]*sin(rotation_angle_rad); } for (size_t i = 0; i < 3; ++i) { - q_[i] = rotation_axis[i] * sin(rotation_angle_rad); + quaternion_[i] = rotation_axis[i] * sin(rotation_angle_rad); } } @@ -35,22 +35,22 @@ Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_a Vector<3> op = outer_product(normalized_v_before, normalized_v_after); if (ip > 1.0 - DBL_EPSILON) { // if theta=0, then rotation is not need - q_[0] = 0.0; - q_[1] = 0.0; - q_[2] = 0.0; - q_[3] = 1.0; + quaternion_[0] = 0.0; + quaternion_[1] = 0.0; + quaternion_[2] = 0.0; + quaternion_[3] = 1.0; } else if (ip < -1.0 + DBL_EPSILON) { // if theta=180deg, the rotation rotation_axis can't be defined, so rotate vector_before manually Vector<3> rotation_axis = GenerateOrthoUnitVector(vector_before); - q_[0] = rotation_axis[0], q_[1] = rotation_axis[1], q_[2] = rotation_axis[2], q_[3] = 0.0; + quaternion_[0] = rotation_axis[0], quaternion_[1] = rotation_axis[1], quaternion_[2] = rotation_axis[2], quaternion_[3] = 0.0; } else { assert(norm(op) > 0.0); Vector<3> rotation_axis = 1.0 / norm(op) * op; double rotation_angle = acos(ip); - q_[0] = rotation_axis[0] * sin(0.5 * rotation_angle); - q_[1] = rotation_axis[1] * sin(0.5 * rotation_angle); - q_[2] = rotation_axis[2] * sin(0.5 * rotation_angle); - q_[3] = cos(0.5 * rotation_angle); + quaternion_[0] = rotation_axis[0] * sin(0.5 * rotation_angle); + quaternion_[1] = rotation_axis[1] * sin(0.5 * rotation_angle); + quaternion_[2] = rotation_axis[2] * sin(0.5 * rotation_angle); + quaternion_[3] = cos(0.5 * rotation_angle); } } @@ -103,22 +103,22 @@ Quaternion operator*(const double& lhs, const Quaternion& rhs) { Quaternion Quaternion::Normalize(void) { double n = 0.0; for (int i = 0; i < 4; ++i) { - n += pow(q_[i], 2.0); + n += pow(quaternion_[i], 2.0); } if (n == 0.0) { - return q_; + return quaternion_; } // zero Quaternion n = 1.0 / sqrt(n); for (int i = 0; i < 4; ++i) { - q_[i] *= n; + quaternion_[i] *= n; } - return q_; + return quaternion_; } Quaternion Quaternion::Conjugate(void) const { - Quaternion temp(q_); + Quaternion temp(quaternion_); for (int i = 0; i < 3; ++i) { temp[i] *= -1.0; } @@ -128,17 +128,17 @@ Quaternion Quaternion::Conjugate(void) const { Matrix<3, 3> Quaternion::ConvertToDcm(void) const { Matrix<3, 3> dcm; - dcm[0][0] = q_[3] * q_[3] + q_[0] * q_[0] - q_[1] * q_[1] - q_[2] * q_[2]; - dcm[0][1] = 2.0 * (q_[0] * q_[1] + q_[3] * q_[2]); - dcm[0][2] = 2.0 * (q_[0] * q_[2] - q_[3] * q_[1]); + dcm[0][0] = quaternion_[3] * quaternion_[3] + quaternion_[0] * quaternion_[0] - quaternion_[1] * quaternion_[1] - quaternion_[2] * quaternion_[2]; + dcm[0][1] = 2.0 * (quaternion_[0] * quaternion_[1] + quaternion_[3] * quaternion_[2]); + dcm[0][2] = 2.0 * (quaternion_[0] * quaternion_[2] - quaternion_[3] * quaternion_[1]); - dcm[1][0] = 2.0 * (q_[0] * q_[1] - q_[3] * q_[2]); - dcm[1][1] = q_[3] * q_[3] - q_[0] * q_[0] + q_[1] * q_[1] - q_[2] * q_[2]; - dcm[1][2] = 2.0 * (q_[1] * q_[2] + q_[3] * q_[0]); + dcm[1][0] = 2.0 * (quaternion_[0] * quaternion_[1] - quaternion_[3] * quaternion_[2]); + dcm[1][1] = quaternion_[3] * quaternion_[3] - quaternion_[0] * quaternion_[0] + quaternion_[1] * quaternion_[1] - quaternion_[2] * quaternion_[2]; + dcm[1][2] = 2.0 * (quaternion_[1] * quaternion_[2] + quaternion_[3] * quaternion_[0]); - dcm[2][0] = 2.0 * (q_[0] * q_[2] + q_[3] * q_[1]); - dcm[2][1] = 2.0 * (q_[1] * q_[2] - q_[3] * q_[0]); - dcm[2][2] = q_[3] * q_[3] - q_[0] * q_[0] - q_[1] * q_[1] + q_[2] * q_[2]; + dcm[2][0] = 2.0 * (quaternion_[0] * quaternion_[2] + quaternion_[3] * quaternion_[1]); + dcm[2][1] = 2.0 * (quaternion_[1] * quaternion_[2] - quaternion_[3] * quaternion_[0]); + dcm[2][2] = quaternion_[3] * quaternion_[3] - quaternion_[0] * quaternion_[0] - quaternion_[1] * quaternion_[1] + quaternion_[2] * quaternion_[2]; return dcm; } @@ -215,7 +215,7 @@ Quaternion Quaternion::ConvertFromEuler(Vector<3> euler) { Vector<3> Quaternion::FrameConversion(const Vector<3>& vector) const { Quaternion conj = Conjugate(); Quaternion temp1 = conj * vector; - Quaternion temp2 = temp1 * q_; + Quaternion temp2 = temp1 * quaternion_; Vector<3> ans; for (int i = 0; i < 3; ++i) { ans[i] = temp2[i]; @@ -225,7 +225,7 @@ Vector<3> Quaternion::FrameConversion(const Vector<3>& vector) const { Vector<3> Quaternion::InverseFrameConversion(const Vector<3>& vector) const { Quaternion conj = Conjugate(); - Quaternion temp1 = q_ * vector; + Quaternion temp1 = quaternion_ * vector; Quaternion temp2 = temp1 * conj; Vector<3> ans; for (int i = 0; i < 3; ++i) { @@ -234,6 +234,6 @@ Vector<3> Quaternion::InverseFrameConversion(const Vector<3>& vector) const { return ans; } -Vector<4> Quaternion::ConvertToVector() { return q_; } +Vector<4> Quaternion::ConvertToVector() { return quaternion_; } } // namespace libra diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index 10edd17e8..dd8167585 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -148,7 +148,7 @@ class Quaternion { Vector<4> ConvertToVector(); private: - Vector<4> q_; //!< Vector to store the element of quaternion + Vector<4> quaternion_; //!< Vector to store the element of quaternion }; /** diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index c48440a14..62ddcef05 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -11,24 +11,24 @@ namespace libra { Quaternion::Quaternion() {} Quaternion::Quaternion(double q_x, double q_y, double q_z, double q_w) { - q_[0] = q_x; - q_[1] = q_y; - q_[2] = q_z; - q_[3] = q_w; + quaternion_[0] = q_x; + quaternion_[1] = q_y; + quaternion_[2] = q_z; + quaternion_[3] = q_w; } -Quaternion::Quaternion(const Vector<4>& quaternion_vector) : q_(quaternion_vector) {} +Quaternion::Quaternion(const Vector<4>& quaternion_vector) : quaternion_(quaternion_vector) {} Quaternion& Quaternion::operator=(const Vector<4>& quaternion_vector) { - q_ = quaternion_vector; + quaternion_ = quaternion_vector; return *this; } -Quaternion::operator double*() { return q_; } +Quaternion::operator double*() { return quaternion_; } -Quaternion::operator const double*() const { return q_; } +Quaternion::operator const double*() const { return quaternion_; } -Quaternion::operator const Vector<4>&() const { return q_; } +Quaternion::operator const Vector<4>&() const { return quaternion_; } } // namespace libra From d6603180f5cf10ddc6569f65c3ac490c85be440f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:14:42 +0100 Subject: [PATCH 0697/1086] Fix function argument name --- src/library/math/quaternion.cpp | 12 ++++++------ src/library/math/quaternion.hpp | 16 ++++++++-------- src/library/math/quaternion_inline_functions.hpp | 10 +++++----- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 1129decb7..fbc564528 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -11,14 +11,14 @@ namespace libra { -Quaternion::Quaternion(const Vector<3>& rotation_axis, double rotation_angle_rad) { - rotation_angle_rad *= 0.5; - quaternion_[3] = cos(rotation_angle_rad); +Quaternion::Quaternion(const Vector<3>& rotation_axis, const double rotation_angle_rad) { + double half_rotation_angle_rad = rotation_angle_rad * 0.5; + quaternion_[3] = cos(half_rotation_angle_rad); // Vector<3> norm = normalize(rotation_axis); // for(size_t i=0; i<3; ++i){ quaternion_[i] = norm[i]*sin(rotation_angle_rad); } for (size_t i = 0; i < 3; ++i) { - quaternion_[i] = rotation_axis[i] * sin(rotation_angle_rad); + quaternion_[i] = rotation_axis[i] * sin(half_rotation_angle_rad); } } @@ -143,7 +143,7 @@ Matrix<3, 3> Quaternion::ConvertToDcm(void) const { return dcm; } -Quaternion Quaternion::ConvertFromDcm(Matrix<3, 3> dcm) { +Quaternion Quaternion::ConvertFromDcm(const Matrix<3, 3> dcm) { Quaternion q; q[0] = sqrt(1 + dcm[0][0] - dcm[1][1] - dcm[2][2]) / 2; q[1] = sqrt(1 - dcm[0][0] + dcm[1][1] - dcm[2][2]) / 2; @@ -193,7 +193,7 @@ Vector<3> Quaternion::ConvertToEuler(void) const { return eul; } -Quaternion Quaternion::ConvertFromEuler(Vector<3> euler) { +Quaternion Quaternion::ConvertFromEuler(const Vector<3> euler) { double esin[3], ecos[3]; for (int i = 0; i < 3; i++) { esin[i] = sin(euler[i]); diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index dd8167585..f340368b1 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -25,12 +25,12 @@ class Quaternion { /** * @fn Quaternion * @brief Constructor with initialization - * @param [in] q_x: The first element of Quaternion (X) - * @param [in] q_y: The second element of Quaternion (Y) - * @param [in] q_z: The third element of Quaternion (Z) - * @param [in] q_w: The fourth element of Quaternion (W) + * @param [in] quaternion_x: The first element of Quaternion (X) + * @param [in] quaternion_y: The second element of Quaternion (Y) + * @param [in] quaternion_z: The third element of Quaternion (Z) + * @param [in] quaternion_w: The fourth element of Quaternion (W) */ - inline Quaternion(double q_x, double q_y, double q_z, double q_w); + inline Quaternion(const double quaternion_x, const double quaternion_y, const double quaternion_z, const double quaternion_w); /** * @fn Quaternion * @brief Constructor initialized with vector @@ -43,7 +43,7 @@ class Quaternion { * @param [in] rotation_axis: Rotation axis normalized vector * @param [in] rotation_angle_rad: Rotation angle [rad] */ - Quaternion(const Vector<3>& rotation_axis, double rotation_angle_rad); + Quaternion(const Vector<3>& rotation_axis, const double rotation_angle_rad); /** * @fn Quaternion * @brief Constructor initialized with rotates vector_before to match vector_after @@ -107,7 +107,7 @@ class Quaternion { * @param [in] dcm: DCM * @return Quaternion */ - static Quaternion ConvertFromDcm(Matrix<3, 3> dcm); + static Quaternion ConvertFromDcm(const Matrix<3, 3> dcm); /** * @fn ConvertToEuler @@ -122,7 +122,7 @@ class Quaternion { * @param [in] euler: 3-2-1 Euler angle (1, 2, 3 order) * @return Quaternion */ - static Quaternion ConvertFromEuler(Vector<3> euler); + static Quaternion ConvertFromEuler(const Vector<3> euler); /** * @fn FrameConversion diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index 62ddcef05..b039cf0be 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -10,11 +10,11 @@ namespace libra { Quaternion::Quaternion() {} -Quaternion::Quaternion(double q_x, double q_y, double q_z, double q_w) { - quaternion_[0] = q_x; - quaternion_[1] = q_y; - quaternion_[2] = q_z; - quaternion_[3] = q_w; +Quaternion::Quaternion(const double quaternion_x, const double quaternion_y, const double quaternion_z, const double quaternion_w) { + quaternion_[0] = quaternion_x; + quaternion_[1] = quaternion_y; + quaternion_[2] = quaternion_z; + quaternion_[3] = quaternion_w; } Quaternion::Quaternion(const Vector<4>& quaternion_vector) : quaternion_(quaternion_vector) {} From 792a5897e5a233c337e77cb0359d620154351cd3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:18:31 +0100 Subject: [PATCH 0698/1086] Fix local function variables --- src/library/math/quaternion.cpp | 42 ++++++++++++++++----------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index fbc564528..1a5cb1e57 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -149,17 +149,17 @@ Quaternion Quaternion::ConvertFromDcm(const Matrix<3, 3> dcm) { q[1] = sqrt(1 - dcm[0][0] + dcm[1][1] - dcm[2][2]) / 2; q[2] = sqrt(1 - dcm[0][0] - dcm[1][1] + dcm[2][2]) / 2; q[3] = sqrt(1 + dcm[0][0] + dcm[1][1] + dcm[2][2]) / 2; - double maxval = 0; - int maxidx = 0; + double max_value = 0; + int max_index = 0; for (int i = 0; i < 4; i++) { // Scan maximum value index - if (std::abs(q[i]) > maxval) { - maxval = std::abs(q[i]); - maxidx = i; + if (std::abs(q[i]) > max_value) { + max_value = std::abs(q[i]); + max_index = i; } } // Use the maximum value as denominator - switch (maxidx) { + switch (max_index) { case 0: q[1] = (dcm[0][1] + dcm[1][0]) / (4 * q[0]); q[2] = (dcm[0][2] + dcm[2][0]) / (4 * q[0]); @@ -186,11 +186,11 @@ Quaternion Quaternion::ConvertFromDcm(const Matrix<3, 3> dcm) { Vector<3> Quaternion::ConvertToEuler(void) const { auto dcm = this->ConvertToDcm(); - Vector<3> eul; - eul[0] = atan2(dcm[1][2], dcm[2][2]); - eul[1] = atan2(-dcm[0][2], sqrt(dcm[1][2] * dcm[1][2] + dcm[2][2] * dcm[2][2])); - eul[2] = atan2(dcm[0][1], dcm[0][0]); - return eul; + Vector<3> euler; + euler[0] = atan2(dcm[1][2], dcm[2][2]); + euler[1] = atan2(-dcm[0][2], sqrt(dcm[1][2] * dcm[1][2] + dcm[2][2] * dcm[2][2])); + euler[2] = atan2(dcm[0][1], dcm[0][0]); + return euler; } Quaternion Quaternion::ConvertFromEuler(const Vector<3> euler) { @@ -213,25 +213,25 @@ Quaternion Quaternion::ConvertFromEuler(const Vector<3> euler) { } Vector<3> Quaternion::FrameConversion(const Vector<3>& vector) const { - Quaternion conj = Conjugate(); - Quaternion temp1 = conj * vector; + Quaternion conjugate = Conjugate(); + Quaternion temp1 = conjugate * vector; Quaternion temp2 = temp1 * quaternion_; - Vector<3> ans; + Vector<3> answer; for (int i = 0; i < 3; ++i) { - ans[i] = temp2[i]; + answer[i] = temp2[i]; } - return ans; + return answer; } Vector<3> Quaternion::InverseFrameConversion(const Vector<3>& vector) const { - Quaternion conj = Conjugate(); + Quaternion conjugate = Conjugate(); Quaternion temp1 = quaternion_ * vector; - Quaternion temp2 = temp1 * conj; - Vector<3> ans; + Quaternion temp2 = temp1 * conjugate; + Vector<3> answer; for (int i = 0; i < 3; ++i) { - ans[i] = temp2[i]; + answer[i] = temp2[i]; } - return ans; + return answer; } Vector<4> Quaternion::ConvertToVector() { return quaternion_; } From 853580442b8f30806b702d0b4c065cf913d25c08 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 16:29:09 +0100 Subject: [PATCH 0699/1086] Fix public function names --- src/dynamics/attitude/attitude_rk4.cpp | 4 +-- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/library/math/matrix_vector.hpp | 28 +++++++++---------- .../math/matrix_vector_template_functions.hpp | 28 +++++++++---------- 4 files changed, 31 insertions(+), 31 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index f9caac4b5..408934e45 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -19,7 +19,7 @@ AttitudeRk4::AttitudeRk4(const libra::Vector<3>& angular_velocity_b_rad_s, const inertia_tensor_kgm2_ = inertia_tensor_kgm2; propagation_step_s_ = propagation_step_s; current_propagation_time_s_ = 0.0; - inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); + inv_inertia_tensor_ = CalcInverseMatrix(inertia_tensor_kgm2_); angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); CalcAngularMomentum(); } @@ -32,7 +32,7 @@ void AttitudeRk4::SetParameters(const MCSimExecutor& mc_simulator) { // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; - inv_inertia_tensor_ = libra::invert(inertia_tensor_kgm2_); + inv_inertia_tensor_ = libra::CalcInverseMatrix(inertia_tensor_kgm2_); angular_momentum_reaction_wheel_b_Nms_ = libra::Vector<3>(0.0); //!< Consider how to handle this variable CalcAngularMomentum(); } diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 07222b9ca..4a87fdc77 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -21,7 +21,7 @@ ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, cons orbit_(orbit) { quaternion_i2b_ = quaternion_i2b; inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: inertia tensor should be initialized in the Attitude base class - inv_inertia_tensor_ = invert(inertia_tensor_kgm2_); + inv_inertia_tensor_ = CalcInverseMatrix(inertia_tensor_kgm2_); Initialize(); } diff --git a/src/library/math/matrix_vector.hpp b/src/library/math/matrix_vector.hpp index da0bac226..870c18259 100644 --- a/src/library/math/matrix_vector.hpp +++ b/src/library/math/matrix_vector.hpp @@ -14,43 +14,43 @@ namespace libra { /** * @fn operator* * @brief Multiply matrix and vector - * @param [in] m: Target matrix - * @param [in] m: Target vector + * @param [in] matrix: Target matrix + * @param [in] vector: Target vector * @return Result of multiplied matrix */ template -Vector operator*(const Matrix& m, const Vector& v); +Vector operator*(const Matrix& matrix, const Vector& vector); /** - * @fn invert + * @fn CalcInverseMatrix * @brief Calculate inverse matrix - * @param [in] a: Target matrix - * @return Result of invert matrix + * @param [in] matrix: Target matrix + * @return Inverse matrix */ template -Matrix invert(const Matrix& a); +Matrix CalcInverseMatrix(const Matrix& matrix); /** - * @fn ludcmp + * @fn LuDecomposition * @brief LU decomposition * @note Warning: a is overwritten. - * @param [in/out] a: Target matrix + * @param [in/out] matrix: Target matrix * @param [in] index: Array to store row/column switch information * @return Result of LU decomposed matrix */ template -Matrix& ludcmp(Matrix& a, unsigned int index[]); +Matrix& LuDecomposition(Matrix& matrix, unsigned int index[]); /** - * @fn lubksb + * @fn SolveLinearSystemWithLu * @brief Solve linear system of equation with LU decomposition - * @param [in] a: LU decomposed coefficient matrix + * @param [in] matrix: LU decomposed coefficient matrix * @param [in] index: Array to store row/column switch information - * @param [in] b: Right hand side vector of the linear system + * @param [in] vector: Right hand side vector of the linear system * @return Result vector */ template -Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& b); +Vector& SolveLinearSystemWithLu(const Matrix& matrix, const unsigned int index[], Vector& vector); } // namespace libra diff --git a/src/library/math/matrix_vector_template_functions.hpp b/src/library/math/matrix_vector_template_functions.hpp index 8a41ef78c..c4b0e42c6 100644 --- a/src/library/math/matrix_vector_template_functions.hpp +++ b/src/library/math/matrix_vector_template_functions.hpp @@ -11,37 +11,37 @@ namespace libra { template -Vector operator*(const Matrix& m, const Vector& v) { +Vector operator*(const Matrix& matrix, const Vector& vector) { Vector temp(0.0); for (size_t i = 0; i < R; ++i) { for (size_t j = 0; j < C; ++j) { - temp[i] += m[i][j] * v[j]; + temp[i] += matrix[i][j] * vector[j]; } } return temp; } template -Matrix invert(const Matrix& a) { - Matrix temp(a); +Matrix CalcInverseMatrix(const Matrix& matrix) { + Matrix temp(matrix); unsigned int index[N]; - ludcmp(temp, index); + LuDecomposition(temp, index); - Matrix inv; - Vector v; + Matrix inverse; + Vector vector; for (size_t i = 0; i < N; ++i) { - fill_up(v, 0.0); - v[i] = 1.0; - lubksb(temp, index, v); + fill_up(vector, 0.0); + vector[i] = 1.0; + SolveLinearSystemWithLu(temp, index, vector); for (size_t j = 0; j < N; ++j) { - inv[j][i] = v[j]; + inverse[j][i] = vector[j]; } } - return inv; + return inverse; } template -Matrix& ludcmp(Matrix& a, unsigned int index[]) { +Matrix& LuDecomposition(Matrix& a, unsigned int index[]) { double coef[N]; for (size_t i = 0; i < N; ++i) { double biggest = 0.0; @@ -109,7 +109,7 @@ Matrix& ludcmp(Matrix& a, unsigned int index[]) { } template -Vector& lubksb(const Matrix& a, const unsigned int index[], Vector& b) { +Vector& SolveLinearSystemWithLu(const Matrix& a, const unsigned int index[], Vector& b) { double sum; bool non_zero = false; unsigned int mark = 0; From d710ec9e2dfc4eccc4a3d3ce96f30bb312fe8654 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:08:52 +0100 Subject: [PATCH 0700/1086] Fix private function name --- src/library/math/matrix.hpp | 4 ++-- src/library/math/matrix_inline_functions.hpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index b48a87c31..e4dc0676d 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -120,13 +120,13 @@ class Matrix { T matrix_[R][C]; //!< Array to save the elements /** - * @fn is_valid_range_ + * @fn ISValidRange * @brief Judge the target row/column number is in the range * @param [in] row: Target row number * @param [in] column: Target column number * @return True: row/column number is in the range */ - inline bool is_valid_range_(size_t row, size_t column); + inline bool ISValidRange(size_t row, size_t column); }; /** diff --git a/src/library/math/matrix_inline_functions.hpp b/src/library/math/matrix_inline_functions.hpp index 2ce1b73d7..d709e434c 100644 --- a/src/library/math/matrix_inline_functions.hpp +++ b/src/library/math/matrix_inline_functions.hpp @@ -35,7 +35,7 @@ Matrix::operator CTP() const { template T& Matrix::operator()(size_t row, size_t column) { - if (!is_valid_range_(row, column)) { + if (!ISValidRange(row, column)) { throw std::invalid_argument("Argument exceeds the range of matrix."); } return matrix_[row][column]; @@ -43,14 +43,14 @@ T& Matrix::operator()(size_t row, size_t column) { template const T& Matrix::operator()(size_t row, size_t column) const { - if (!is_valid_range_(row, column)) { + if (!ISValidRange(row, column)) { throw std::invalid_argument("Argument exceeds the range of matrix."); } return matrix_[row][column]; } template -bool Matrix::is_valid_range_(size_t row, size_t column) { +bool Matrix::ISValidRange(size_t row, size_t column) { return (row < R && column < C); } From e37c4856570eb5a0e7149dce8548e8fe688beeb5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:15:39 +0100 Subject: [PATCH 0701/1086] Move inline functions --- src/library/math/matrix.hpp | 27 +++++++---- src/library/math/matrix_inline_functions.hpp | 48 +------------------- 2 files changed, 19 insertions(+), 56 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index e4dc0676d..910a7acde 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -22,7 +22,7 @@ class Matrix { * @fn Matrix * @brief Default constructor without any initialization */ - inline Matrix(); + inline Matrix() {} /** * @fn Matrix @@ -38,27 +38,27 @@ class Matrix { * @fn row * @brief Return row number */ - inline size_t row() const; + inline size_t row() const { return R; } /** * @fn row * @brief Return column number */ - inline size_t column() const; + inline size_t column() const { return C; } /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 2D-array using `[]` * @return Pointer to the data storing array */ - inline operator TP(); + inline operator TP() { return matrix_; } /** * @fn Cast operator to directly access the elements (const ver.) * @brief Operator to access the elements similar with the 2D-array using `[]` * @return Const pointer to the data storing array */ - inline operator CTP() const; + inline operator CTP() const { return matrix_; } /** * @fn Operator () @@ -68,7 +68,12 @@ class Matrix { * @param [in] column: Target column number * @return Value of the target element */ - inline T& operator()(size_t row, size_t column); + inline T& operator()(size_t row, size_t column) { + if (!ISValidRange(row, column)) { + throw std::invalid_argument("Argument exceeds the range of matrix."); + } + return matrix_[row][column]; + } /** * @fn Operator () @@ -78,7 +83,12 @@ class Matrix { * @param [in] column: Target column number * @return Value of the target element */ - inline const T& operator()(size_t row, size_t column) const; + inline const T& operator()(size_t row, size_t column) const { + if (!ISValidRange(row, column)) { + throw std::invalid_argument("Argument exceeds the range of matrix."); + } + return matrix_[row][column]; + } /** * @fn Operator += @@ -126,7 +136,7 @@ class Matrix { * @param [in] column: Target column number * @return True: row/column number is in the range */ - inline bool ISValidRange(size_t row, size_t column); + inline bool ISValidRange(size_t row, size_t column) { return (row < R && column < C); } }; /** @@ -253,7 +263,6 @@ Matrix rotz(const double& theta); } // namespace libra -#include "matrix_inline_functions.hpp" #include "matrix_template_functions.hpp" #endif // S2E_LIBRARY_MATH_MATRIX_HPP_ diff --git a/src/library/math/matrix_inline_functions.hpp b/src/library/math/matrix_inline_functions.hpp index d709e434c..f8ba2aba3 100644 --- a/src/library/math/matrix_inline_functions.hpp +++ b/src/library/math/matrix_inline_functions.hpp @@ -8,52 +8,6 @@ #include // for invalid_argument -namespace libra { - -template -Matrix::Matrix() {} - -template -size_t Matrix::row() const { - return R; -} - -template -size_t Matrix::column() const { - return C; -} - -template -Matrix::operator TP() { - return matrix_; -} - -template -Matrix::operator CTP() const { - return matrix_; -} - -template -T& Matrix::operator()(size_t row, size_t column) { - if (!ISValidRange(row, column)) { - throw std::invalid_argument("Argument exceeds the range of matrix."); - } - return matrix_[row][column]; -} - -template -const T& Matrix::operator()(size_t row, size_t column) const { - if (!ISValidRange(row, column)) { - throw std::invalid_argument("Argument exceeds the range of matrix."); - } - return matrix_[row][column]; -} - -template -bool Matrix::ISValidRange(size_t row, size_t column) { - return (row < R && column < C); -} - -} // namespace libra +namespace libra {} // namespace libra #endif // S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ From 7766362ae9644f2b2aca11ad4f50955648a48593 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:16:04 +0100 Subject: [PATCH 0702/1086] Delete unnecessary file --- src/library/math/matrix_inline_functions.hpp | 13 ------------- 1 file changed, 13 deletions(-) delete mode 100644 src/library/math/matrix_inline_functions.hpp diff --git a/src/library/math/matrix_inline_functions.hpp b/src/library/math/matrix_inline_functions.hpp deleted file mode 100644 index f8ba2aba3..000000000 --- a/src/library/math/matrix_inline_functions.hpp +++ /dev/null @@ -1,13 +0,0 @@ -/** - * @file matrix_inline_functions.hpp - * @brief Matrix class to handle math matrix with template - */ - -#ifndef S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ -#define S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ - -#include // for invalid_argument - -namespace libra {} // namespace libra - -#endif // S2E_LIBRARY_MATH_MATRIX_INLINE_FUNCTIONS_HPP_ From 20c9cf8d25b9ca3fc0f7bd391920826569a20b2e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:18:32 +0100 Subject: [PATCH 0703/1086] Fix public function name --- src/library/math/matrix.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 910a7acde..d83ed9000 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -35,16 +35,16 @@ class Matrix { typedef const T (*CTP)[C]; //!< Define the const pointer of the array as CTP type /** - * @fn row + * @fn GetRowLength * @brief Return row number */ - inline size_t row() const { return R; } + inline size_t GetRowLength() const { return R; } /** - * @fn row + * @fn GetColumnLength * @brief Return column number */ - inline size_t column() const { return C; } + inline size_t GetColumnLength() const { return C; } /** * @fn Cast operator to directly access the elements From c5a8b97372fa2c58a8fba0f620763d8ab60f92b3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:39:56 +0100 Subject: [PATCH 0704/1086] Fix public function name --- src/disturbances/geopotential.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/environment/global/celestial_rotation.cpp | 20 +++++------ src/library/math/matrix.hpp | 34 +++++++++---------- .../math/matrix_template_functions.hpp | 28 +++++++-------- src/library/orbit/kepler_orbit.cpp | 6 ++-- .../ground_station/ground_station.cpp | 2 +- 7 files changed, 47 insertions(+), 47 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 8b6628c73..352ea3adf 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -79,7 +79,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam #endif Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelestialInformation().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); - Matrix<3, 3> trans_ecef2eci = transpose(trans_eci2ecef_); + Matrix<3, 3> trans_ecef2eci = Transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 4a87fdc77..71f773cfa 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -96,7 +96,7 @@ void ControlledAttitude::PointingControl(const libra::Vector<3> main_direction_i // Calc DCM Target->body libra::Matrix<3, 3> dcm_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body - libra::Matrix<3, 3> dcm_i2b = dcm_t2b * transpose(dcm_t2i); + libra::Matrix<3, 3> dcm_i2b = dcm_t2b * Transpose(dcm_t2i); // Convert to Quaternion quaternion_i2b_ = Quaternion::ConvertFromDcm(dcm_i2b); } diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index a7df118cb..d2bf28445 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -20,7 +20,7 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "Anonymous"; rotation_mode_ = Idle; - unitalize(dcm_j2000_to_xcxf_); + Unitalize(dcm_j2000_to_xcxf_); dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; if (center_body_name == "EARTH") { InitCelestialRotationAsEarth(rotation_mode, center_body_name); @@ -115,12 +115,12 @@ void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation } else { // If the rotation mode is neither Simple nor Full, disable the rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - unitalize(dcm_j2000_to_xcxf_); + Unitalize(dcm_j2000_to_xcxf_); } } else { // If the center object is not the Earth, disable the Earth's rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - unitalize(dcm_j2000_to_xcxf_); + Unitalize(dcm_j2000_to_xcxf_); } } @@ -167,7 +167,7 @@ void CelestialRotation::Update(const double JulianDate) { } } -libra::Matrix<3, 3> CelestialRotation::AxialRotation(const double GAST_rad) { return libra::rotz(GAST_rad); } +libra::Matrix<3, 3> CelestialRotation::AxialRotation(const double GAST_rad) { return libra::MakeRotationMatrixZ(GAST_rad); } libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) { // Mean obliquity of the ecliptic @@ -221,9 +221,9 @@ libra::Matrix<3, 3> CelestialRotation::Nutation(const double (&tTT_century)[4]) c_d_epsilon_rad_[7] * cos(2 * L_rad + lm_rad) + c_d_epsilon_rad_[8] * cos(2 * Ld_rad - ls_rad); // [rad] double epsi_mod_rad = epsilon_rad_ + d_epsilon_rad_; - libra::Matrix<3, 3> X_epsi_1st = libra::rotx(epsilon_rad_); - libra::Matrix<3, 3> Z_dpsi = libra::rotz(-d_psi_rad_); - libra::Matrix<3, 3> X_epsi_2nd = libra::rotx(-epsi_mod_rad); + libra::Matrix<3, 3> X_epsi_1st = libra::MakeRotationMatrixX(epsilon_rad_); + libra::Matrix<3, 3> Z_dpsi = libra::MakeRotationMatrixZ(-d_psi_rad_); + libra::Matrix<3, 3> X_epsi_2nd = libra::MakeRotationMatrixX(-epsi_mod_rad); libra::Matrix<3, 3> N; N = X_epsi_2nd * Z_dpsi * X_epsi_1st; @@ -247,9 +247,9 @@ libra::Matrix<3, 3> CelestialRotation::Precession(const double (&tTT_century)[4] } // Develop transformation matrix - libra::Matrix<3, 3> Z_zeta = libra::rotz(-zeta_rad); - libra::Matrix<3, 3> Y_theta = libra::roty(theta_rad); - libra::Matrix<3, 3> Z_z = libra::rotz(-z_rad); + libra::Matrix<3, 3> Z_zeta = libra::MakeRotationMatrixZ(-zeta_rad); + libra::Matrix<3, 3> Y_theta = libra::MakeRotationMatrixY(theta_rad); + libra::Matrix<3, 3> Z_z = libra::MakeRotationMatrixZ(-z_rad); libra::Matrix<3, 3> P; P = Z_z * Y_theta * Z_zeta; diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index d83ed9000..8e0b76248 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -146,16 +146,16 @@ class Matrix { * @param [in] t: Scalar value to fill up */ template -void fill_up(Matrix& m, const T& t); +void FillUp(Matrix& m, const T& t); /** - * @fn trace - * @brief Calculate and return the trace of matrix + * @fn CalcTrace + * @brief Calculate and return the CalcTrace of matrix * @param [in] m: Target matrix * @return Trace of the matrix */ template -T trace(const Matrix& m); +T CalcTrace(const Matrix& m); /** * @fn print @@ -165,7 +165,7 @@ T trace(const Matrix& m); * @param [out] stream: Output target(Default: cout) */ template -void print(const Matrix& m, char delimiter = '\t', std::ostream& stream = std::cout); +void Print(const Matrix& m, char delimiter = '\t', std::ostream& stream = std::cout); /** * @fn operator + @@ -208,58 +208,58 @@ template const Matrix operator*(const Matrix& lhs, const Matrix& rhs); /** - * @fn transpose + * @fn Transpose * @brief Calculate and return transposed matrix * @param [in] m: Target matrix * @return Result of transposed matrix */ template -const Matrix transpose(const Matrix& m); +const Matrix Transpose(const Matrix& m); /** - * @fn unitalize + * @fn Unitalize * @brief Rewrite the input matrix as the identity matrix * @note Warning: m is overwritten. * @param [in/out] m: Target matrix * @return The identity matrix */ template -Matrix& unitalize(Matrix& m); +Matrix& Unitalize(Matrix& m); /** - * @fn eye + * @fn MakeIdentityMatrix * @brief Generate identity matrix * @return The identity matrix */ template -Matrix eye(); +Matrix MakeIdentityMatrix(); /** - * @fn rotx + * @fn MakeRotationMatrixX * @brief Generate 3*3 rotation matrix around X-axis * @param [in] theta: Rotation angle [rad] * @return Rotation matrix */ template -Matrix rotx(const double& theta); +Matrix MakeRotationMatrixX(const double& theta); /** - * @fn roty + * @fn MakeRotationMatrixY * @brief Generate 3*3 rotation matrix around Y-axis * @param [in] theta: Rotation angle [rad] * @return Rotation matrix */ template -Matrix roty(const double& theta); +Matrix MakeRotationMatrixY(const double& theta); /** - * @fn rotz + * @fn MakeRotationMatrixZ * @brief Generate 3*3 rotation matrix around Z-axis * @param [in] theta: Rotation angle [rad] * @return Rotation matrix */ template -Matrix rotz(const double& theta); +Matrix MakeRotationMatrixZ(const double& theta); } // namespace libra diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 8f88e04aa..d66e1efbe 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -56,7 +56,7 @@ const Matrix& Matrix::operator-=(const Matrix& m) { } template -void fill_up(Matrix& m, const T& t) { +void FillUp(Matrix& m, const T& t) { for (size_t i = 0; i < R; ++i) { for (size_t j = 0; j < C; ++j) { m[i][j] = t; @@ -65,7 +65,7 @@ void fill_up(Matrix& m, const T& t) { } template -T trace(const Matrix& m) { +T CalcTrace(const Matrix& m) { T trace = 0.0; for (size_t i = 0; i < N; ++i) { trace += m[i][i]; @@ -74,7 +74,7 @@ T trace(const Matrix& m) { } template -void print(const Matrix& m, char delimiter, std::ostream& stream) { +void Print(const Matrix& m, char delimiter, std::ostream& stream) { for (size_t i = 0; i < R; ++i) { stream << m[i][0]; for (size_t j = 1; j < C; ++j) { @@ -131,7 +131,7 @@ const Matrix operator*(const Matrix& lhs, const Matrix -const Matrix transpose(const Matrix& m) { +const Matrix Transpose(const Matrix& m) { Matrix temp; for (size_t i = 0; i < R; ++i) { for (size_t j = 0; j < C; ++j) { @@ -142,8 +142,8 @@ const Matrix transpose(const Matrix& m) { } template -Matrix& unitalize(Matrix& m) { - fill_up(m, 0.0); +Matrix& Unitalize(Matrix& m) { + FillUp(m, 0.0); for (size_t i = 0; i < R; ++i) { m[i][i] = 1.0; } @@ -151,16 +151,16 @@ Matrix& unitalize(Matrix& m) { } template -Matrix eye() { +Matrix MakeIdentityMatrix() { Matrix m; - unitalize(m); + Unitalize(m); return m; } template -Matrix rotx(const double& theta) { +Matrix MakeRotationMatrixX(const double& theta) { Matrix m; - unitalize(m); + Unitalize(m); m[1][1] = cos(theta); m[1][2] = sin(theta); m[2][1] = -sin(theta); @@ -169,9 +169,9 @@ Matrix rotx(const double& theta) { } template -Matrix roty(const double& theta) { +Matrix MakeRotationMatrixY(const double& theta) { Matrix m; - unitalize(m); + Unitalize(m); m[0][0] = cos(theta); m[0][2] = -sin(theta); m[2][0] = sin(theta); @@ -180,9 +180,9 @@ Matrix roty(const double& theta) { } template -Matrix rotz(const double& theta) { +Matrix MakeRotationMatrixZ(const double& theta) { Matrix m; - unitalize(m); + Unitalize(m); m[0][0] = cos(theta); m[0][1] = sin(theta); m[1][0] = -sin(theta); diff --git a/src/library/orbit/kepler_orbit.cpp b/src/library/orbit/kepler_orbit.cpp index 9816ff036..8f6e68d29 100644 --- a/src/library/orbit/kepler_orbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -20,9 +20,9 @@ void KeplerOrbit::CalcConstKeplerMotion() { mean_motion_rad_s_ = sqrt(mu_m3_s2_ / a_m3); // DCM - libra::Matrix<3, 3> dcm_arg_perigee = libra::rotz(-1.0 * oe_.GetArgPerigee_rad()); - libra::Matrix<3, 3> dcm_inclination = libra::rotx(-1.0 * oe_.GetInclination_rad()); - libra::Matrix<3, 3> dcm_raan = libra::rotz(-1.0 * oe_.GetRaan_rad()); + libra::Matrix<3, 3> dcm_arg_perigee = libra::MakeRotationMatrixZ(-1.0 * oe_.GetArgPerigee_rad()); + libra::Matrix<3, 3> dcm_inclination = libra::MakeRotationMatrixX(-1.0 * oe_.GetInclination_rad()); + libra::Matrix<3, 3> dcm_raan = libra::MakeRotationMatrixZ(-1.0 * oe_.GetRaan_rad()); libra::Matrix<3, 3> dcm_inc_arg = dcm_inclination * dcm_arg_perigee; dcm_inplane_to_i_ = dcm_raan * dcm_inc_arg; } diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 548a8c790..38229e578 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -45,7 +45,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft) { - Matrix<3, 3> dcm_ecef2eci = transpose(celes_rotation.GetDcmJ2000ToXcxf()); + Matrix<3, 3> dcm_ecef2eci = Transpose(celes_rotation.GetDcmJ2000ToXcxf()); gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; is_visible_[spacecraft.GetSatID()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); From 525b35c795ba8aadf66f589af07d917703e7bd36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:41:30 +0100 Subject: [PATCH 0705/1086] Fix function arguments --- src/library/math/matrix.hpp | 12 ++++---- .../math/matrix_template_functions.hpp | 30 +++++++++---------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 8e0b76248..42749f891 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -237,29 +237,29 @@ Matrix MakeIdentityMatrix(); /** * @fn MakeRotationMatrixX * @brief Generate 3*3 rotation matrix around X-axis - * @param [in] theta: Rotation angle [rad] + * @param [in] theta_rad: Rotation angle [rad] * @return Rotation matrix */ template -Matrix MakeRotationMatrixX(const double& theta); +Matrix MakeRotationMatrixX(const double& theta_rad); /** * @fn MakeRotationMatrixY * @brief Generate 3*3 rotation matrix around Y-axis - * @param [in] theta: Rotation angle [rad] + * @param [in] theta_rad: Rotation angle [rad] * @return Rotation matrix */ template -Matrix MakeRotationMatrixY(const double& theta); +Matrix MakeRotationMatrixY(const double& theta_rad); /** * @fn MakeRotationMatrixZ * @brief Generate 3*3 rotation matrix around Z-axis - * @param [in] theta: Rotation angle [rad] + * @param [in] theta_rad: Rotation angle [rad] * @return Rotation matrix */ template -Matrix MakeRotationMatrixZ(const double& theta); +Matrix MakeRotationMatrixZ(const double& theta_rad); } // namespace libra diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index d66e1efbe..089f135c3 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -158,35 +158,35 @@ Matrix MakeIdentityMatrix() { } template -Matrix MakeRotationMatrixX(const double& theta) { +Matrix MakeRotationMatrixX(const double& theta_rad) { Matrix m; Unitalize(m); - m[1][1] = cos(theta); - m[1][2] = sin(theta); - m[2][1] = -sin(theta); - m[2][2] = cos(theta); + m[1][1] = cos(theta_rad); + m[1][2] = sin(theta_rad); + m[2][1] = -sin(theta_rad); + m[2][2] = cos(theta_rad); return m; } template -Matrix MakeRotationMatrixY(const double& theta) { +Matrix MakeRotationMatrixY(const double& theta_rad) { Matrix m; Unitalize(m); - m[0][0] = cos(theta); - m[0][2] = -sin(theta); - m[2][0] = sin(theta); - m[2][2] = cos(theta); + m[0][0] = cos(theta_rad); + m[0][2] = -sin(theta_rad); + m[2][0] = sin(theta_rad); + m[2][2] = cos(theta_rad); return m; } template -Matrix MakeRotationMatrixZ(const double& theta) { +Matrix MakeRotationMatrixZ(const double& theta_rad) { Matrix m; Unitalize(m); - m[0][0] = cos(theta); - m[0][1] = sin(theta); - m[1][0] = -sin(theta); - m[1][1] = cos(theta); + m[0][0] = cos(theta_rad); + m[0][1] = sin(theta_rad); + m[1][0] = -sin(theta_rad); + m[1][1] = cos(theta_rad); return m; } From 04c2ec0f3dc413fa9a2775a6b25d046b73805b73 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:45:21 +0100 Subject: [PATCH 0706/1086] Move inline functions --- src/library/math/vector.hpp | 23 ++++++++---- src/library/math/vector_inline_functions.hpp | 38 +------------------- 2 files changed, 17 insertions(+), 44 deletions(-) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 40e7e738a..617c7854e 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -24,7 +24,7 @@ class Vector { * @fn Vector * @brief Constructor without any initialization */ - inline Vector(); + inline Vector() {} /** * @fn Vector * @brief Constructor with initialize the elements as all same value @@ -36,21 +36,21 @@ class Vector { * @fn dim * @brief Return number of elements */ - inline size_t dim() const; + inline size_t dim() const { return N; } /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 1D-array using `[]` * @return Pointer to the data storing array */ - inline operator T*(); + inline operator T*() { return vector_; } /** * @fn Cast operator to directly access the elements (const ver.) * @brief Operator to access the elements similar with the 1D-array using `[]` * @return Pointer to the data storing array */ - inline operator const T*() const; + inline operator const T*() const { return vector_; } /** * @fn Operator () @@ -59,7 +59,12 @@ class Vector { * @param [in] pos: Target element number * @return Value of the target element */ - inline T& operator()(std::size_t pos); + inline T& operator()(std::size_t pos) { + if (N <= pos) { + throw std::invalid_argument("Argument exceeds Vector's dimension."); + } + return vector_[pos]; + } /** * @fn Operator () @@ -68,7 +73,12 @@ class Vector { * @param [in] pos: Target element number * @return Value of the target element */ - inline T operator()(std::size_t pos) const; + inline T operator()(std::size_t pos) const { + if (N <= pos) { + throw std::invalid_argument("Argument exceeds Vector's dimension."); + } + return vector_[pos]; + } /** * @fn Operator += @@ -245,7 +255,6 @@ Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v); } // namespace libra -#include "vector_inline_functions.hpp" #include "vector_template_functions.hpp" #endif // S2E_LIBRARY_MATH_VECTOR_HPP_ diff --git a/src/library/math/vector_inline_functions.hpp b/src/library/math/vector_inline_functions.hpp index 1b436b254..5f599d574 100644 --- a/src/library/math/vector_inline_functions.hpp +++ b/src/library/math/vector_inline_functions.hpp @@ -8,42 +8,6 @@ #include // for invalid_argument. -namespace libra { - -template -Vector::Vector() {} - -template -size_t Vector::dim() const { - return N; -} - -template -Vector::operator T*() { - return vector_; -} - -template -Vector::operator const T*() const { - return vector_; -} - -template -T& Vector::operator()(std::size_t pos) { - if (N <= pos) { - throw std::invalid_argument("Argument exceeds Vector's dimension."); - } - return vector_[pos]; -} - -template -T Vector::operator()(std::size_t pos) const { - if (N <= pos) { - throw std::invalid_argument("Argument exceeds Vector's deimension."); - } - return vector_[pos]; -} - -} // namespace libra +namespace libra {} // namespace libra #endif // S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ From 1fb85aacb46466fdccf5485c6c1fbfa404186f7a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:45:59 +0100 Subject: [PATCH 0707/1086] Delete unnecessary file --- src/library/math/vector_inline_functions.hpp | 13 ------------- 1 file changed, 13 deletions(-) delete mode 100644 src/library/math/vector_inline_functions.hpp diff --git a/src/library/math/vector_inline_functions.hpp b/src/library/math/vector_inline_functions.hpp deleted file mode 100644 index 5f599d574..000000000 --- a/src/library/math/vector_inline_functions.hpp +++ /dev/null @@ -1,13 +0,0 @@ -/** - * @file vector_inline_functions.hpp - * @brief Class for mathematical vector (inline functions) - */ - -#ifndef S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ -#define S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ - -#include // for invalid_argument. - -namespace libra {} // namespace libra - -#endif // S2E_LIBRARY_MATH_VECTOR_IFS_HPP_ From 5796387a00f05351ae210122fb949203b082121d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:47:49 +0100 Subject: [PATCH 0708/1086] Fix function argument name --- src/library/math/vector.hpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 617c7854e..2639d87b5 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -56,28 +56,28 @@ class Vector { * @fn Operator () * @brief Operator to access the element value * @details This operator has assertion to detect range over - * @param [in] pos: Target element number + * @param [in] position: Target element number * @return Value of the target element */ - inline T& operator()(std::size_t pos) { - if (N <= pos) { + inline T& operator()(std::size_t position) { + if (N <= position) { throw std::invalid_argument("Argument exceeds Vector's dimension."); } - return vector_[pos]; + return vector_[position]; } /** * @fn Operator () * @brief Operator to access the element value (const ver.) * @details This operator has assertion to detect range over - * @param [in] pos: Target element number + * @param [in] position: Target element number * @return Value of the target element */ - inline T operator()(std::size_t pos) const { - if (N <= pos) { + inline T operator()(std::size_t position) const { + if (N <= position) { throw std::invalid_argument("Argument exceeds Vector's dimension."); } - return vector_[pos]; + return vector_[position]; } /** From f4d1f3e03a7e13d32a448cd64caa48c96acd6aaa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:58:59 +0100 Subject: [PATCH 0709/1086] Fix public functions name --- src/components/ideal/force_generator.cpp | 10 ++--- src/components/ideal/torque_generator.cpp | 10 ++--- src/components/real/aocs/gnss_receiver.cpp | 14 +++---- src/components/real/aocs/magnetorquer.cpp | 2 +- src/components/real/aocs/reaction_wheel.cpp | 2 +- src/components/real/aocs/star_sensor.cpp | 10 ++--- src/components/real/aocs/sun_sensor.cpp | 8 ++-- .../ground_station_calculator.cpp | 6 +-- src/components/real/mission/telescope.cpp | 6 +-- .../real/power/solar_array_panel.cpp | 14 +++---- .../real/propulsion/simple_thruster.cpp | 6 +-- src/disturbances/air_drag.cpp | 4 +- src/disturbances/gravity_gradient.cpp | 4 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/surface_force.cpp | 14 +++---- src/disturbances/third_body_gravity.cpp | 4 +- src/dynamics/attitude/attitude.cpp | 4 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 20 ++++----- .../orbit/encke_orbit_propagation.cpp | 16 +++---- src/dynamics/orbit/orbit.cpp | 12 +++--- src/dynamics/orbit/relative_orbit.cpp | 4 +- src/dynamics/thermal/node.cpp | 4 +- src/dynamics/thermal/temperature.cpp | 2 +- src/environment/global/gnss_satellites.cpp | 2 +- .../local/local_celestial_information.cpp | 2 +- .../solar_radiation_pressure_environment.cpp | 10 ++--- src/library/external/sgp4/sgp4ext.cpp | 8 ++-- src/library/external/sgp4/sgp4ext.h | 2 +- src/library/math/matrix.hpp | 2 +- .../math/matrix_vector_template_functions.hpp | 2 +- ...fferential_equation_template_functions.hpp | 6 +-- src/library/math/quaternion.cpp | 22 +++++----- src/library/math/vector.cpp | 18 ++++---- src/library/math/vector.hpp | 42 +++++++++---------- .../math/vector_template_functions.hpp | 18 ++++---- src/library/orbit/orbital_elements.cpp | 10 ++--- .../ground_station/ground_station.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 14 +++---- .../relative_information.cpp | 4 +- .../structure/initialize_structure.cpp | 4 +- .../spacecraft/structure/surface.hpp | 2 +- 43 files changed, 176 insertions(+), 176 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 2ff0271b1..5e622ac14 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -25,10 +25,10 @@ void ForceGenerator::MainRoutine(int count) { generated_force_b_N_ = ordered_force_b_N_; // Add noise - double norm_ordered_force = norm(ordered_force_b_N_); + double norm_ordered_force = CalcNorm(ordered_force_b_N_); if (norm_ordered_force > 0.0 + DBL_EPSILON) { // Add noise only when the force is generated - libra::Vector<3> true_direction = normalize(generated_force_b_N_); + libra::Vector<3> true_direction = Normalize(generated_force_b_N_); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_force_b_N_); double force_norm_with_error = norm_ordered_force + magnitude_noise_; @@ -89,11 +89,11 @@ libra::Quaternion ForceGenerator::GenerateDirectionNoiseQuaternion(libra::Vector random_direction[0] = direction_noise_; random_direction[1] = direction_noise_; random_direction[2] = direction_noise_; - random_direction = normalize(random_direction); + random_direction = Normalize(random_direction); libra::Vector<3> rotation_axis; - rotation_axis = outer_product(true_direction, random_direction); - double norm_rotation_axis = norm(rotation_axis); + rotation_axis = OuterProduct(true_direction, random_direction); + double norm_rotation_axis = CalcNorm(rotation_axis); if (norm_rotation_axis < 0.0 + DBL_EPSILON) { // No rotation error if the randomized direction is parallel to the true direction rotation_axis = true_direction; diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 894b95276..6fde1d1c1 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -25,10 +25,10 @@ void TorqueGenerator::MainRoutine(int count) { generated_torque_b_Nm_ = ordered_torque_b_Nm_; // Add noise - double norm_ordered_torque = norm(ordered_torque_b_Nm_); + double norm_ordered_torque = CalcNorm(ordered_torque_b_Nm_); if (norm_ordered_torque > 0.0 + DBL_EPSILON) { // Add noise only when the torque is generated - libra::Vector<3> true_direction = normalize(generated_torque_b_Nm_); + libra::Vector<3> true_direction = Normalize(generated_torque_b_Nm_); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_torque_b_Nm_); double torque_norm_with_error = norm_ordered_torque + magnitude_noise_; @@ -62,11 +62,11 @@ libra::Quaternion TorqueGenerator::GenerateDirectionNoiseQuaternion(libra::Vecto random_direction[0] = direction_noise_; random_direction[1] = direction_noise_; random_direction[2] = direction_noise_; - random_direction = normalize(random_direction); + random_direction = Normalize(random_direction); libra::Vector<3> rotation_axis; - rotation_axis = outer_product(true_direction, random_direction); - double norm_rotation_axis = norm(rotation_axis); + rotation_axis = OuterProduct(true_direction, random_direction); + double norm_rotation_axis = CalcNorm(rotation_axis); if (norm_rotation_axis < 0.0 + DBL_EPSILON) { // No rotation error if the randomized direction is parallel to the true direction rotation_axis = true_direction; diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 5765b76df..4278d75a7 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -85,7 +85,7 @@ void GNSSReceiver::CheckAntennaSimple(const Vector<3> pos_true_eci_, Quaternion Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); - double inner = inner_product(pos_true_eci_, antenna_direction_i); + double inner = InnerProduct(pos_true_eci_, antenna_direction_i); if (inner <= 0) is_gnss_sats_visible_ = 0; else @@ -119,18 +119,18 @@ void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_ // compute direction from sat to gnss in body-fixed frame gnss_sat_pos_i = gnss_satellites_->GetSatellitePositionEci(i); ant2gnss_i = gnss_sat_pos_i - ant_pos_i; - double normalizer = 1 / norm(ant2gnss_i); + double normalizer = 1 / CalcNorm(ant2gnss_i); ant2gnss_i_n = normalizer * ant2gnss_i; // check gnss sats are visible from antenna double Re = environment::earth_equatorial_radius_m; - double inner1 = inner_product(ant_pos_i, gnss_sat_pos_i); + double inner1 = InnerProduct(ant_pos_i, gnss_sat_pos_i); int is_visible_ant2gnss = 0; if (inner1 > 0) is_visible_ant2gnss = 1; else { - Vector<3> tmp = ant_pos_i + inner_product(-ant_pos_i, ant2gnss_i_n) * ant2gnss_i; - if (norm(tmp) < Re) + Vector<3> tmp = ant_pos_i + InnerProduct(-ant_pos_i, ant2gnss_i_n) * ant2gnss_i; + if (CalcNorm(tmp) < Re) // There is earth between antenna and gnss is_visible_ant2gnss = 0; else @@ -138,7 +138,7 @@ void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_ is_visible_ant2gnss = 1; } - double inner2 = inner_product(antenna_direction_i, ant2gnss_i_n); + double inner2 = InnerProduct(antenna_direction_i, ant2gnss_i_n); if (inner2 > cos(half_width_ * libra::deg_to_rad) && is_visible_ant2gnss) { // is visible gnss_sats_visible_num_++; @@ -158,7 +158,7 @@ void GNSSReceiver::SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::stri ant2gnss_b = q_i2b.FrameConversion(ant2gnss_i); ant2gnss_c = q_b2c_.FrameConversion(ant2gnss_b); - double dist = norm(ant2gnss_c); + double dist = CalcNorm(ant2gnss_c); double lon = AcTan(ant2gnss_c[1], ant2gnss_c[0]); double lat = AcTan(ant2gnss_c[2], sqrt(pow(ant2gnss_c[0], 2.0) + pow(ant2gnss_c[1], 2.0))); diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index b02fadcb6..433736f0a 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -74,7 +74,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { // Frame conversion component to body mag_moment_b_ = q_c2b_.FrameConversion(mag_moment_c_); // Calc magnetic torque [Nm] - torque_b_ = outer_product(mag_moment_b_, knT2T * mag_env_->GetGeomagneticFieldneticField_b_nT()); + torque_b_ = OuterProduct(mag_moment_b_, knT2T * mag_env_->GetGeomagneticFieldneticField_b_nT()); // Update Random Walk ++n_rw_c_; diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index b0bbb2013..89e6f2c27 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -152,7 +152,7 @@ libra::Vector<3> RWModel::CalcTorque() { const libra::Vector<3> RWModel::GetOutputTorqueB() const { if (is_calculated_jitter_) { // Add jitter_force_b_-derived torque and jitter_torque_b_ to output_torqur_b - return output_torque_b_ - libra::outer_product(pos_b_, rw_jitter_.GetJitterForceB()) - rw_jitter_.GetJitterTorqueB(); + return output_torque_b_ - libra::OuterProduct(pos_b_, rw_jitter_.GetJitterForceB()) - rw_jitter_.GetJitterTorqueB(); } else { return output_torque_b_; } diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 87ead57c2..a45bd6e46 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -147,7 +147,7 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { Quaternion q_c2b = q_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, - norm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge + CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge double earth_center_angle_rad = CalAngleVect_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight double earth_edge_angle_rad = earth_center_angle_rad - earth_size_rad; // angles between sat<->earth_edge & sat_sight if (earth_edge_angle_rad < earth_forbidden_angle_) @@ -167,7 +167,7 @@ int STT::MoonJudgement(const libra::Vector<3>& moon_b) { } int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b) { - double omega_norm = norm(omega_b); + double omega_norm = CalcNorm(omega_b); if (omega_norm > capture_rate_) return 1; else @@ -196,10 +196,10 @@ std::string STT::GetLogValue() const { double STT::CalAngleVect_rad(const Vector<3>& vect1, const Vector<3>& vect2) { Vector<3> vect1_normal(vect1); - normalize(vect1_normal); // Normalize Vector1 + Normalize(vect1_normal); // Normalize Vector1 Vector<3> vect2_normal(vect2); - normalize(vect2_normal); // Normalize Vector2 - double cosTheta = inner_product(vect1_normal, vect2_normal); // Calc cos value + Normalize(vect2_normal); // Normalize Vector2 + double cosTheta = InnerProduct(vect1_normal, vect2_normal); // Calc cos value double theta_rad = acos(cosTheta); return theta_rad; } diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index a104c2cbd..1f35c66a9 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -58,7 +58,7 @@ void SunSensor::MainRoutine(int count) { void SunSensor::measure() { libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); - libra::Vector<3> sun_dir_b = normalize(sun_pos_b); + libra::Vector<3> sun_dir_b = Normalize(sun_pos_b); sun_c_ = q_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component @@ -83,7 +83,7 @@ void SunSensor::measure() { measured_sun_c_[1] = tan(beta_); measured_sun_c_[2] = 1.0; - measured_sun_c_ = normalize(measured_sun_c_); + measured_sun_c_ = Normalize(measured_sun_c_); } else { measured_sun_c_ = libra::Vector<3>(0); alpha_ = 0.0; @@ -94,7 +94,7 @@ void SunSensor::measure() { } void SunSensor::SunDetectionJudgement() { - libra::Vector<3> sun_direction_c = normalize(sun_c_); + libra::Vector<3> sun_direction_c = Normalize(sun_c_); double sun_angle_ = acos(sun_direction_c[2]); @@ -110,7 +110,7 @@ void SunSensor::SunDetectionJudgement() { } void SunSensor::CalcSolarIlluminance() { - libra::Vector<3> sun_direction_c = normalize(sun_c_); + libra::Vector<3> sun_direction_c = Normalize(sun_c_); double sun_angle_ = acos(sun_direction_c[2]); if (sun_angle_ > libra::pi_2) { diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index d75c33b17..3e8975246 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -67,12 +67,12 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetGSPosition_i(); - double dist_sc_gs_km = norm(sc_pos_i - gs_pos_i) / 1000.0; + double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / sc_tx_ant.GetFrequency() / 1000.0)); // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; - sc_to_gs_i = libra::normalize(sc_to_gs_i); + sc_to_gs_i = libra::Normalize(sc_to_gs_i); Quaternion q_i_to_sc_ant = sc_tx_ant.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_ant_rad = acos(gs_direction_on_sc_frame[2]); @@ -80,7 +80,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); - gs_to_sc_ecef = libra::normalize(gs_to_sc_ecef); + gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); Quaternion q_ecef_to_gs_ant = gs_rx_ant.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_ant_rad = acos(sc_direction_on_gs_frame[2]); diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 1ee407d02..84d4146ec 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -73,15 +73,15 @@ void Telescope::MainRoutine(int count) { // sun_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); // earth_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); // moon_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); - // angle_sun = angle(sight_, sun_pos_c) * 180/libra::pi; - // angle_earth = angle(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = angle(sight_, moon_pos_c) * 180 / libra::pi; + // angle_sun = CalcAngleTwoVectors_rad(sight_, sun_pos_c) * 180/libra::pi; + // angle_earth = CalcAngleTwoVectors_rad(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = CalcAngleTwoVectors_rad(sight_, moon_pos_c) * 180 / libra::pi; //****************************************************************************** } bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { Quaternion q_c2b = q_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); - double angle_rad = libra::angle(target_b, sight_b); + double angle_rad = libra::CalcAngleTwoVectors_rad(target_b, sight_b); if (angle_rad < forbidden_angle) { return true; } else diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 1684093c0..df21f1c3b 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -16,7 +16,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), - normal_vector_(libra::normalize(normal_vector)), + normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), @@ -34,7 +34,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), - normal_vector_(libra::normalize(normal_vector)), + normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), @@ -51,7 +51,7 @@ SAP::SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_ number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), - normal_vector_(libra::normalize(normal_vector)), + normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), @@ -101,15 +101,15 @@ void SAP::MainRoutine(int time_count) { double time_query = compo_step_time_ * time_count; const auto solar_constant = srp_->GetSolarConstant_W_m2(); libra::Vector<3> sun_direction_body = CsvScenarioInterface::GetSunDirectionBody(time_query); - libra::Vector<3> normalized_sun_direction_body = libra::normalize(sun_direction_body); + libra::Vector<3> normalized_sun_direction_body = libra::Normalize(sun_direction_body); power_generation_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * - cell_area_ * number_of_parallel_ * number_of_series_ * inner_product(normal_vector_, normalized_sun_direction_body); + cell_area_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, normalized_sun_direction_body); } else { const auto power_density = srp_->GetPowerDensity_W_m2(); libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); - libra::Vector<3> sun_dir_b = libra::normalize(sun_pos_b); + libra::Vector<3> sun_dir_b = libra::Normalize(sun_pos_b); power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * - inner_product(normal_vector_, sun_dir_b); + InnerProduct(normal_vector_, sun_dir_b); // TODO: Improve implementation. For example, update IV curve with sun direction and calculate generated power } if (power_generation_ < 0) power_generation_ = 0.0; diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 2e5953392..44bb8af0e 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -42,7 +42,7 @@ SimpleThruster::~SimpleThruster() {} void SimpleThruster::Initialize(const double mag_err, const double dir_err) { mag_nr_.SetParameters(0.0, mag_err); dir_nr_.SetParameters(0.0, dir_err); - thrust_dir_b_ = normalize(thrust_dir_b_); + thrust_dir_b_ = Normalize(thrust_dir_b_); } void SimpleThruster::MainRoutine(int count) { @@ -65,7 +65,7 @@ void SimpleThruster::CalcThrust() { void SimpleThruster::CalcTorque(Vector<3> center) { Vector<3> vector_center2thruster = thruster_pos_b_ - center; - Vector<3> torque = outer_product(vector_center2thruster, thrust_b_); + Vector<3> torque = OuterProduct(vector_center2thruster, thrust_b_); torque_b_ = torque; } @@ -85,7 +85,7 @@ std::string SimpleThruster::GetLogValue() const { str_tmp += WriteVector(thrust_b_); str_tmp += WriteVector(torque_b_); - str_tmp += WriteScalar(norm(thrust_b_)); + str_tmp += WriteScalar(CalcNorm(thrust_b_)); return str_tmp; } diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index a57d4307c..7d67ac9dc 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -29,7 +29,7 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& } void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3) { - double velocity_norm_m_s = norm(velocity_b_m_s); + double velocity_norm_m_s = CalcNorm(velocity_b_m_s); CalcCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); @@ -53,7 +53,7 @@ double AirDrag::CalcFunctionChi(const double s) { } void AirDrag::CalcCnCt(const Vector<3>& velocity_b_m_s) { - double velocity_norm_m_s = norm(velocity_b_m_s); + double velocity_norm_m_s = CalcNorm(velocity_b_m_s); // Re-emitting speed double speed = diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 83a3be60d..546e9511a 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -23,12 +23,12 @@ void GravityGradient::Update(const LocalEnvironment& local_environment, const Dy libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { - double r_norm_m = norm(earth_position_from_sc_b_m); + double r_norm_m = CalcNorm(earth_position_from_sc_b_m); libra::Vector<3> u_b = earth_position_from_sc_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; double coeff = 3.0 * gravity_constant_m3_s2_ / pow(r_norm_m, 3.0); - torque_b_Nm_ = coeff * outer_product(u_b, inertia_tensor_b_kgm2 * u_b); + torque_b_Nm_ = coeff * OuterProduct(u_b, inertia_tensor_b_kgm2 * u_b); return torque_b_Nm_; } diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 2a547f580..caf70f7fc 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -19,7 +19,7 @@ MagneticDisturbance::MagneticDisturbance(const RMMParams& rmm_params, const bool Vector<3> MagneticDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { CalcRMM(); - torque_b_Nm_ = kMagUnit_ * outer_product(rmm_b_Am2_, magnetic_field_b_nT); + torque_b_Nm_ = kMagUnit_ * OuterProduct(rmm_b_Am2_, magnetic_field_b_nT); return torque_b_Nm_; } diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index d0b3d651a..19a213297 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -24,20 +24,20 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction libra::Vector<3> force_b_N(0.0); libra::Vector<3> torque_b_Nm(0.0); libra::Vector<3> input_b_normal(input_direction_b); - normalize(input_b_normal); + Normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { if (cos_theta_[i] > 0.0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force libra::Vector<3> normal = surfaces_[i].GetNormal(); - libra::Vector<3> ncu = outer_product(input_b_normal, normal); - libra::Vector<3> ncu_normalized = normalize(ncu); - libra::Vector<3> in_plane_force_direction = outer_product(ncu_normalized, normal); + libra::Vector<3> ncu = OuterProduct(input_b_normal, normal); + libra::Vector<3> ncu_normalized = Normalize(ncu); + libra::Vector<3> in_plane_force_direction = OuterProduct(ncu_normalized, normal); // calc force libra::Vector<3> force_per_surface_b_N = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * in_plane_force_direction; force_b_N += force_per_surface_b_N; // calc torque - torque_b_Nm += outer_product(surfaces_[i].GetPosition() - center_of_gravity_b_m_, force_per_surface_b_N); + torque_b_Nm += OuterProduct(surfaces_[i].GetPosition() - center_of_gravity_b_m_, force_per_surface_b_N); } } force_b_N_ = force_b_N; @@ -47,10 +47,10 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction void SurfaceForce::CalcTheta(libra::Vector<3>& input_direction_b) { libra::Vector<3> input_b_normal(input_direction_b); - normalize(input_b_normal); + Normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { - cos_theta_[i] = inner_product(surfaces_[i].GetNormal(), input_b_normal); + cos_theta_[i] = InnerProduct(surfaces_[i].GetNormal(), input_b_normal); sin_theta_[i] = sqrt(1.0 - cos_theta_[i] * cos_theta_[i]); } } diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 7cbeed512..61f3a358a 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -29,10 +29,10 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> ThirdBodyGravity::CalcAcceleration_i_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { libra::Vector<3> acceleration_i_m_s2; - double s_norm = libra::norm(s); + double s_norm = libra::CalcNorm(s); double s_norm3 = s_norm * s_norm * s_norm; - double sr_norm = libra::norm(sr); + double sr_norm = libra::CalcNorm(sr); double sr_norm3 = sr_norm * sr_norm * sr_norm; acceleration_i_m_s2 = gravity_constant_m_s2 * (1.0 / sr_norm3 * sr - 1.0 / s_norm3 * s); diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index a8e13a83a..aaf719c05 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -49,7 +49,7 @@ void Attitude::CalcAngularMomentum(void) { angular_momentum_total_b_Nms_ = angular_momentum_reaction_wheel_b_Nms_ + angular_momentum_spacecraft_b_Nms_; libra::Quaternion q_b2i = quaternion_i2b_.Conjugate(); angular_momentum_total_i_Nms_ = q_b2i.FrameConversion(angular_momentum_total_b_Nms_); - angular_momentum_total_Nms_ = norm(angular_momentum_total_i_Nms_); + angular_momentum_total_Nms_ = CalcNorm(angular_momentum_total_i_Nms_); - kinetic_energy_J_ = 0.5 * libra::inner_product(angular_momentum_spacecraft_b_Nms_, angular_velocity_b_rad_s_); + kinetic_energy_J_ = 0.5 * libra::InnerProduct(angular_momentum_spacecraft_b_Nms_, angular_velocity_b_rad_s_); } diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index b25997043..15b4d4beb 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -50,7 +50,7 @@ class Attitude : public ILoggable, public SimulationObject { * @fn GetTotalAngMomNorm * @brief Return norm of total angular momentum of the spacecraft [Nms] */ - inline double GetTotalAngMomNorm() const { return libra::norm(angular_momentum_total_b_Nms_); } + inline double GetTotalAngMomNorm() const { return libra::CalcNorm(angular_momentum_total_b_Nms_); } /** * @fn GetEnergy * @brief Return rotational Kinetic Energy of Spacecraft [J] diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 408934e45..2f27eb25d 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -82,7 +82,7 @@ libra::Vector<7> AttitudeRk4::AttitudeDynamicsAndKinematics(libra::Vector<7> x, omega_b[i] = x[i]; } angular_momentum_total_b_Nms_ = (inertia_tensor_kgm2_ * omega_b) + angular_momentum_reaction_wheel_b_Nms_; - libra::Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::outer_product(omega_b, angular_momentum_total_b_Nms_)); + libra::Vector<3> rhs = inv_inertia_tensor_ * (torque_b_Nm_ - libra::OuterProduct(omega_b, angular_momentum_total_b_Nms_)); for (int i = 0; i < 3; ++i) { dxdt[i] = rhs[i]; diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 71f773cfa..cc332ac54 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -42,9 +42,9 @@ void ControlledAttitude::Initialize(void) { return; } // pointing direction check - normalize(main_target_direction_b_); - normalize(sub_target_direction_b_); - double tmp = inner_product(main_target_direction_b_, sub_target_direction_b_); + Normalize(main_target_direction_b_); + Normalize(sub_target_direction_b_); + double tmp = InnerProduct(main_target_direction_b_, sub_target_direction_b_); tmp = std::abs(tmp); if (tmp > cos(kMinDirectionAngle_rad)) { std::cout << "sub target direction should separate from the main target direction. \n"; @@ -84,9 +84,9 @@ Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { } else if (mode == VELOCITY_DIRECTION_POINTING) { direction = orbit_->GetVelocity_i_m_s(); } else if (mode == ORBIT_NORMAL_POINTING) { - direction = outer_product(orbit_->GetPosition_i_m(), orbit_->GetVelocity_i_m_s()); + direction = OuterProduct(orbit_->GetPosition_i_m(), orbit_->GetVelocity_i_m_s()); } - normalize(direction); + Normalize(direction); return direction; } @@ -105,11 +105,11 @@ libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_dire // Calc basis vectors libra::Vector<3> ex, ey, ez; ex = main_direction; - libra::Vector<3> tmp1 = outer_product(ex, sub_direction); - libra::Vector<3> tmp2 = outer_product(tmp1, ex); - ey = normalize(tmp2); - libra::Vector<3> tmp3 = outer_product(ex, ey); - ez = normalize(tmp3); + libra::Vector<3> tmp1 = OuterProduct(ex, sub_direction); + libra::Vector<3> tmp2 = OuterProduct(tmp1, ex); + ey = Normalize(tmp2); + libra::Vector<3> tmp3 = OuterProduct(ex, ey); + ez = Normalize(tmp3); // Generate DCM libra::Matrix<3, 3> dcm; diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 24dc50c6f..d2c9028ac 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -28,8 +28,8 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) if (!is_calc_enabled_) return; // Rectification - double norm_sat_position_m = norm(spacecraft_position_i_m_); - double norm_difference_position_m = norm(difference_position_i_m_); + double norm_sat_position_m = CalcNorm(spacecraft_position_i_m_); + double norm_difference_position_m = CalcNorm(difference_position_i_m_); if (norm_difference_position_m / norm_sat_position_m > error_tolerance_) { Initialize(current_time_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); } @@ -68,7 +68,7 @@ void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& } double q_func = CalcQFunction(difference_position_i_m_m); - double r_m = norm(reference_position_i_m_); + double r_m = CalcNorm(reference_position_i_m_); double r_m3 = pow(r_m, 3.0); difference_acc_i_m_s2 = @@ -85,7 +85,7 @@ void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& // Private Functions void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> reference_position_i_m, libra::Vector<3> reference_velocity_i_m_s) { // General - fill_up(spacecraft_acceleration_i_m_s2_, 0.0); + FillUp(spacecraft_acceleration_i_m_s2_, 0.0); // reference orbit reference_position_i_m_ = reference_position_i_m; @@ -94,8 +94,8 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> reference_kepler_orbit = KeplerOrbit(gravity_constant_m3_s2_, oe_ref); // difference orbit - fill_up(difference_position_i_m_, 0.0); - fill_up(difference_velocity_i_m_s_, 0.0); + FillUp(difference_position_i_m_, 0.0); + FillUp(difference_velocity_i_m_s_, 0.0); libra::Vector<6> zero(0.0f); Setup(0.0, zero); @@ -113,12 +113,12 @@ void EnckeOrbitPropagation::UpdateSatOrbit() { double EnckeOrbitPropagation::CalcQFunction(libra::Vector<3> difference_position_i_m) { double r2; - r2 = inner_product(spacecraft_position_i_m_, spacecraft_position_i_m_); + r2 = InnerProduct(spacecraft_position_i_m_, spacecraft_position_i_m_); libra::Vector<3> dr_2r; dr_2r = difference_position_i_m - 2.0 * spacecraft_position_i_m_; - double q = inner_product(difference_position_i_m, dr_2r) / r2; + double q = InnerProduct(difference_position_i_m, dr_2r) / r2; double q_func = q * (q * q + 3.0 * q + 3.0) / (pow(1.0 + q, 1.5) + 1.0); diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index 6bf7bdc37..f6054e5fe 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -6,12 +6,12 @@ libra::Quaternion Orbit::CalcQuaternion_i2lvlh() const { libra::Vector<3> lvlh_x = spacecraft_position_i_m_; // x-axis in LVLH frame is position vector direction from geocenter to satellite - libra::Vector<3> lvlh_ex = normalize(lvlh_x); + libra::Vector<3> lvlh_ex = Normalize(lvlh_x); libra::Vector<3> lvlh_z = - outer_product(spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); // z-axis in LVLH frame is angular momentum vector direction of orbit - libra::Vector<3> lvlh_ez = normalize(lvlh_z); - libra::Vector<3> lvlh_y = outer_product(lvlh_z, lvlh_x); - libra::Vector<3> lvlh_ey = normalize(lvlh_y); + OuterProduct(spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); // z-axis in LVLH frame is angular momentum vector direction of orbit + libra::Vector<3> lvlh_ez = Normalize(lvlh_z); + libra::Vector<3> lvlh_y = OuterProduct(lvlh_z, lvlh_x); + libra::Vector<3> lvlh_ey = Normalize(lvlh_y); libra::Matrix<3, 3> dcm_i2lvlh; dcm_i2lvlh[0][0] = lvlh_ex[0]; @@ -35,7 +35,7 @@ void Orbit::TransformEciToEcef(void) { // convert velocity vector in ECI to the vector in ECEF libra::Vector<3> earth_angular_velocity_i_rad_s{0.0}; earth_angular_velocity_i_rad_s[2] = environment::earth_mean_angular_velocity_rad_s; - libra::Vector<3> we_cross_r = outer_product(earth_angular_velocity_i_rad_s, spacecraft_position_i_m_); + libra::Vector<3> we_cross_r = OuterProduct(earth_angular_velocity_i_rad_s, spacecraft_position_i_m_); libra::Vector<3> velocity_we_cross_r = spacecraft_velocity_i_m_s_ - we_cross_r; spacecraft_velocity_ecef_m_s_ = dcm_i_to_xcxf * velocity_we_cross_r; } diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 23c95226f..a39c82f10 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -71,7 +71,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m double gravity_constant_m3_s2) { switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { - double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); + double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); system_matrix_ = CalcHillSystemMatrix(reference_sat_orbit_radius, gravity_constant_m3_s2); } default: { @@ -84,7 +84,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2, double elapsed_sec) { switch (stm_model_type) { case StmModel::HCW: { - double reference_sat_orbit_radius = libra::norm(reference_sat_orbit->GetPosition_i_m()); + double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); stm_ = CalcHcwStm(reference_sat_orbit_radius, gravity_constant_m3_s2, elapsed_sec); } default: { diff --git a/src/dynamics/thermal/node.cpp b/src/dynamics/thermal/node.cpp index a82775434..eea700ad5 100644 --- a/src/dynamics/thermal/node.cpp +++ b/src/dynamics/thermal/node.cpp @@ -62,9 +62,9 @@ double Node::CalcSolarRadiation(libra::Vector<3> sun_direction) { double R = 6.96E+8; // Distance from sun double T = 5778; // sun surface temperature [K] double sigma = 5.67E-8; // stephan-boltzman constant - double a = norm(sun_direction); // distance from sun + double a = CalcNorm(sun_direction); // distance from sun double S = pow((R / a), 2) * sigma * pow(T, 4); // Solar Constant at s/c position S[W/m^2] - double cos_theta = inner_product(sun_direction, normal_v_b_) / a / norm(normal_v_b_); + double cos_theta = InnerProduct(sun_direction, normal_v_b_) / a / CalcNorm(normal_v_b_); // calculate sun_power if (cos_theta > 0) diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index 8eee383d7..25a30fe9f 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -56,7 +56,7 @@ void Temperature::Propagate(libra::Vector<3> sun_direction, const double endtime cout << setprecision(4) << itr->GetSolarRadiation() << " "; } cout << "SunDir: "; - double norm_sund = norm(sun_direction); + double norm_sund = CalcNorm(sun_direction); for (int i = 0; i < 3; i++) { cout << setprecision(3) << sun_direction[i] / norm_sund << " "; } diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 28878c861..fe8213936 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -1068,7 +1068,7 @@ double GnssSatellites::AddIonosphericDelay(const int sat_id, const libra::Vector else if (flag == ECI) gnss_position = true_info_.GetSatellitePositionEci(sat_id); - double angle_rad = angle(rec_position, gnss_position - rec_position); + double angle_rad = CalcAngleTwoVectors_rad(rec_position, gnss_position - rec_position); const double default_delay = 20.0; //[m] default delay double delay = default_delay * (1000.0 - altitude) / 1000.0 / cos(angle_rad); // set the maximum height as 1000.0. Divide by // cos because the slope makes it longer. diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 2fbc8ca81..82398aa4a 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -118,7 +118,7 @@ void LocalCelestialInformation::ConvertVelocityInertialToBody(const double* posi } // compute cross term wxr - libra::Vector<3> wxposition_i = outer_product(wb, ri); + libra::Vector<3> wxposition_i = OuterProduct(wb, ri); // compute dr/dt + wxr for (int i = 0; i < 3; i++) { vi[i] = vi[i] - wxposition_i[i]; diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 271ecb1f6..877cfb882 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -28,7 +28,7 @@ void SolarRadiationPressureEnvironment::UpdateAllStates() { void SolarRadiationPressureEnvironment::UpdatePressure() { const libra::Vector<3> r_sc2sun_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); - const double distance_sat_to_sun = norm(r_sc2sun_eci); + const double distance_sat_to_sun = CalcNorm(r_sc2sun_eci); solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } @@ -62,13 +62,13 @@ void SolarRadiationPressureEnvironment::CalcShadowCoefficient(std::string shadow const double shadow_source_radius_m = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); - const double distance_sat_to_sun = norm(r_sc2sun_eci); - const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun - const double sd_source = asin(shadow_source_radius_m / norm(r_sc2source_eci)); // Apparent radius of the shadow source + const double distance_sat_to_sun = CalcNorm(r_sc2sun_eci); + const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun + const double sd_source = asin(shadow_source_radius_m / CalcNorm(r_sc2source_eci)); // Apparent radius of the shadow source // Angle of deviation from shadow source center to sun center const double delta = - acos(inner_product(r_sc2source_eci, r_sc2sun_eci - r_sc2source_eci) / norm(r_sc2source_eci) / norm(r_sc2sun_eci - r_sc2source_eci)); + acos(InnerProduct(r_sc2source_eci, r_sc2sun_eci - r_sc2source_eci) / CalcNorm(r_sc2source_eci) / CalcNorm(r_sc2sun_eci - r_sc2source_eci)); // The angle between the center of the sun and the common chord const double x = (delta * delta + sd_sun * sd_sun - sd_source * sd_source) / (2.0 * delta); // The length of the common chord of the apparent solar disk and apparent telestial disk diff --git a/src/library/external/sgp4/sgp4ext.cpp b/src/library/external/sgp4/sgp4ext.cpp index 593a93c21..8fffa39e1 100644 --- a/src/library/external/sgp4/sgp4ext.cpp +++ b/src/library/external/sgp4/sgp4ext.cpp @@ -241,7 +241,7 @@ double dot(double x[3], double y[3]) { return (x[0] * y[0] + x[1] * y[1] + x[2] * --------------------------------------------------------------------------- */ -double angle(double vec1[3], double vec2[3]) { +double CalcAngleTwoVectors_rad(double vec1[3], double vec2[3]) { double small, undefined, magv1, magv2, temp; small = 0.00000001; undefined = 999999.1; @@ -492,14 +492,14 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e // ---------------- find argument of perigee --------------- if (strcmp(typeorbit, "ei") == 0) { - argp = angle(nbar, ebar); + argp = CalcAngleTwoVectors_rad(nbar, ebar); if (ebar[2] < 0.0) argp = twopi - argp; } else argp = undefined; // ------------ find true anomaly at epoch ------------- if (typeorbit[0] == 'e') { - nu = angle(ebar, r); + nu = CalcAngleTwoVectors_rad(ebar, r); if (rdotv < 0.0) nu = twopi - nu; } else nu = undefined; @@ -507,7 +507,7 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e // ---- find argument of latitude - circular inclined ----- // 緯度の計算(円の/傾斜面の) if (strcmp(typeorbit, "ci") == 0) { - arglat = angle(nbar, r); + arglat = CalcAngleTwoVectors_rad(nbar, r); if (r[2] < 0.0) arglat = twopi - arglat; m = arglat; } else diff --git a/src/library/external/sgp4/sgp4ext.h b/src/library/external/sgp4/sgp4ext.h index a46d3fcfa..2ebb3fa55 100644 --- a/src/library/external/sgp4/sgp4ext.h +++ b/src/library/external/sgp4/sgp4ext.h @@ -40,7 +40,7 @@ void cross(double[], double[], double[]); double dot(double[], double[]); -double angle(double[], double[]); +double CalcAngleTwoVectors_rad(double[], double[]); void newtonnu(double ecc, double nu, double& e0, double& m); diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 42749f891..24fade351 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -140,7 +140,7 @@ class Matrix { }; /** - * @fn fill_up + * @fn FillUp * @brief Fill up all elements with same value * @param [in] m: Target matrix * @param [in] t: Scalar value to fill up diff --git a/src/library/math/matrix_vector_template_functions.hpp b/src/library/math/matrix_vector_template_functions.hpp index c4b0e42c6..f84d3311d 100644 --- a/src/library/math/matrix_vector_template_functions.hpp +++ b/src/library/math/matrix_vector_template_functions.hpp @@ -30,7 +30,7 @@ Matrix CalcInverseMatrix(const Matrix& matrix) { Matrix inverse; Vector vector; for (size_t i = 0; i < N; ++i) { - fill_up(vector, 0.0); + FillUp(vector, 0.0); vector[i] = 1.0; SolveLinearSystemWithLu(temp, index, vector); for (size_t j = 0; j < N; ++j) { diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index ebeac1cab..7bef1b5f5 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -30,13 +30,13 @@ void OrdinaryDifferentialEquation::Update() { // 4th order Runge-Kutta method Vector k1(derivative_); k1 *= step_width_; - Vector k2(state_.dim()); + Vector k2(state_.GetLength()); DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); k2 *= step_width_; - Vector k3(state_.dim()); + Vector k3(state_.GetLength()); DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); k3 *= step_width_; - Vector k4(state_.dim()); + Vector k4(state_.GetLength()); DerivativeFunction(independent_variable_ + step_width_, state_ + k3, k4); k4 *= step_width_; diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 1a5cb1e57..616c32418 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -15,7 +15,7 @@ Quaternion::Quaternion(const Vector<3>& rotation_axis, const double rotation_ang double half_rotation_angle_rad = rotation_angle_rad * 0.5; quaternion_[3] = cos(half_rotation_angle_rad); - // Vector<3> norm = normalize(rotation_axis); + // Vector<3> norm = Normalize(rotation_axis); // for(size_t i=0; i<3; ++i){ quaternion_[i] = norm[i]*sin(rotation_angle_rad); } for (size_t i = 0; i < 3; ++i) { quaternion_[i] = rotation_axis[i] * sin(half_rotation_angle_rad); @@ -24,15 +24,15 @@ Quaternion::Quaternion(const Vector<3>& rotation_axis, const double rotation_ang Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_after) { // Assert for zero vector - assert(norm(vector_before) > DBL_EPSILON); - assert(norm(vector_after) > DBL_EPSILON); + assert(CalcNorm(vector_before) > DBL_EPSILON); + assert(CalcNorm(vector_after) > DBL_EPSILON); // Normalize - Vector<3> normalized_v_before = 1.0 / norm(vector_before) * vector_before; - Vector<3> normalized_v_after = 1.0 / norm(vector_after) * vector_after; - // inner product (=cosine of the angle(theta) between two vectors) - double ip = inner_product(normalized_v_before, normalized_v_after); + Vector<3> normalized_v_before = 1.0 / CalcNorm(vector_before) * vector_before; + Vector<3> normalized_v_after = 1.0 / CalcNorm(vector_after) * vector_after; + // inner product (=cosine of the CalcAngleTwoVectors_rad(theta) between two vectors) + double ip = InnerProduct(normalized_v_before, normalized_v_after); // outer product (rotation rotation_axis for converting vector_before to vector_after) - Vector<3> op = outer_product(normalized_v_before, normalized_v_after); + Vector<3> op = OuterProduct(normalized_v_before, normalized_v_after); if (ip > 1.0 - DBL_EPSILON) { // if theta=0, then rotation is not need quaternion_[0] = 0.0; @@ -41,11 +41,11 @@ Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_a quaternion_[3] = 1.0; } else if (ip < -1.0 + DBL_EPSILON) { // if theta=180deg, the rotation rotation_axis can't be defined, so rotate vector_before manually - Vector<3> rotation_axis = GenerateOrthoUnitVector(vector_before); + Vector<3> rotation_axis = GenerateOrthogonalUnitVector(vector_before); quaternion_[0] = rotation_axis[0], quaternion_[1] = rotation_axis[1], quaternion_[2] = rotation_axis[2], quaternion_[3] = 0.0; } else { - assert(norm(op) > 0.0); - Vector<3> rotation_axis = 1.0 / norm(op) * op; + assert(CalcNorm(op) > 0.0); + Vector<3> rotation_axis = 1.0 / CalcNorm(op) * op; double rotation_angle = acos(ip); quaternion_[0] = rotation_axis[0] * sin(0.5 * rotation_angle); quaternion_[1] = rotation_axis[1] * sin(0.5 * rotation_angle); diff --git a/src/library/math/vector.cpp b/src/library/math/vector.cpp index 446354053..c9173869c 100644 --- a/src/library/math/vector.cpp +++ b/src/library/math/vector.cpp @@ -8,10 +8,10 @@ #include "constants.hpp" namespace libra { -Vector<3, double> ortho2spher(const Vector<3, double>& ortho) { +Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& ortho) { Vector<3, double> spher; // vector on the polar coordinate - fill_up(spher, 0.0); - spher[0] = norm(ortho); + FillUp(spher, 0.0); + spher[0] = CalcNorm(ortho); // Skip when zero vector if (spher[0] == 0.0) { return spher; @@ -31,8 +31,8 @@ Vector<3, double> ortho2spher(const Vector<3, double>& ortho) { Vector<3, double> ortho2lonlat(const Vector<3, double>& ortho) { Vector<3, double> lonlat; - fill_up(lonlat, 0.0); - lonlat[0] = norm(ortho); + FillUp(lonlat, 0.0); + lonlat[0] = CalcNorm(ortho); // Skip when zero vector if (lonlat[0] == 0.0) { return lonlat; @@ -47,25 +47,25 @@ Vector<3, double> ortho2lonlat(const Vector<3, double>& ortho) { return lonlat; } -Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v) { +Vector<3, double> GenerateOrthogonalUnitVector(const Vector<3, double>& v) { Vector<3> v_ortho; if (v[0] * v[0] <= v[1] * v[1] && v[0] * v[0] <= v[1] * v[1]) { v_ortho[0] = 0.0; v_ortho[1] = v[2]; v_ortho[2] = -v[1]; - v_ortho = normalize(v_ortho); + v_ortho = Normalize(v_ortho); return (v_ortho); } else if (v[1] * v[1] <= v[0] * v[0] && v[1] * v[1] <= v[2] * v[2]) { v_ortho[0] = -v[2]; v_ortho[1] = 0.0; v_ortho[2] = v[0]; - v_ortho = normalize(v_ortho); + v_ortho = Normalize(v_ortho); return (v_ortho); } else { v_ortho[0] = v[1]; v_ortho[1] = -v[0]; v_ortho[2] = 0.0; - v_ortho = normalize(v_ortho); + v_ortho = Normalize(v_ortho); return (v_ortho); } } diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 2639d87b5..982f6efb2 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -9,8 +9,8 @@ #include // for size_t #include // for ostream, cout -#define dot inner_product -#define cross outer_product +#define dot InnerProduct +#define cross OuterProduct namespace libra { /** @@ -36,7 +36,7 @@ class Vector { * @fn dim * @brief Return number of elements */ - inline size_t dim() const { return N; } + inline size_t GetLength() const { return N; } /** * @fn Cast operator to directly access the elements @@ -128,23 +128,23 @@ class Vector { }; /** - * @fn fill_up + * @fn FillUp * @brief Fill up all elements with same value * @param [in] v: Target vector * @param [in] n: Scalar value to fill up */ template -void fill_up(Vector& v, const T& n); +void FillUp(Vector& v, const T& n); /** - * @fn print + * @fn Print * @brief Generate all elements to outstream * @param [in] v: Target vector * @param [in] delimiter: Delimiter (Default: tab) * @param [out] stream: Output target(Default: cout) */ template -void print(const Vector& v, char delimiter = '\t', std::ostream& stream = std::cout); +void Print(const Vector& v, char delimiter = '\t', std::ostream& stream = std::cout); /** * @fn operator + @@ -177,63 +177,63 @@ template const Vector operator*(const T& lhs, const Vector& rhs); /** - * @fn inner_product + * @fn InnerProduct * @brief Inner product of two vectors * @param [in] lhs: Left hand side vector * @param [in] rhs: Right hand side vector * @return Result of scalar value */ template -const T inner_product(const Vector& lhs, const Vector& rhs); +const T InnerProduct(const Vector& lhs, const Vector& rhs); /** - * @fn outer_product + * @fn OuterProduct * @brief Outer product of two vectors * @param [in] lhs: Left hand side vector * @param [in] rhs: Right hand side vector * @return Result vector */ template -const Vector<3, T> outer_product(const Vector<3, T>& lhs, const Vector<3, T>& rhs); +const Vector<3, T> OuterProduct(const Vector<3, T>& lhs, const Vector<3, T>& rhs); /** - * @fn norm + * @fn CalcNorm * @brief Calculate norm of vector * @param [in] v: Target vector * @return Norm of the vector */ template -double norm(const Vector& v); +double CalcNorm(const Vector& v); /** - * @fn normalize + * @fn Normalize * @brief Normalize the target vector * @note Warning: v is overwritten. * @param [in/out] v: Target vector * @return Normalized vector */ template -Vector& normalize(Vector& v); +Vector& Normalize(Vector& v); /** - * @fn angle + * @fn CalcAngleTwoVectors_rad * @brief Calculate angle between two vectors * @param [in] v1: First vector * @param [in] v2: Second vector * @return Angle between v1 and v2 [rad] */ template -double angle(const Vector& v1, const Vector& v2); +double CalcAngleTwoVectors_rad(const Vector& v1, const Vector& v2); /** - * @fn ortho2spher + * @fn ConvertFrameOrthogonal2Polar * @brief Convert orthogonal coordinate (x, y, z) to Polar coordinate (r, theta, phi) * @note 0 <= theta < pi and 0 <= phi < 2pi * Return zero vector when input is zero vector. Return phi = 0 when input vector is on the Z-axis * @param [in] ortho: Vector in orthogonal coordinate * @return Vector in Polar coordinate */ -Vector<3, double> ortho2spher(const Vector<3, double>& ortho); +Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& ortho); /** * @fn ortho2lonlat @@ -245,13 +245,13 @@ Vector<3, double> ortho2spher(const Vector<3, double>& ortho); Vector<3, double> ortho2lonlat(const Vector<3, double>& ortho); /** - * @fn GenerateOrthoUnitVector + * @fn GenerateOrthogonalUnitVector * @brief Generate one unit vector orthogonal to the given 3D vector * @note Vectors orthogonal to the other vector have rotational degree of freedom, which are determined arbitrarily in this function. * @param [in] v: Given vector * @return Generated unit vector that is orthogonal to v */ -Vector<3, double> GenerateOrthoUnitVector(const Vector<3, double>& v); +Vector<3, double> GenerateOrthogonalUnitVector(const Vector<3, double>& v); } // namespace libra diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index a52b78f38..9079f6f70 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -54,14 +54,14 @@ Vector Vector::operator-() const { } template -void fill_up(Vector& v, const T& n) { +void FillUp(Vector& v, const T& n) { for (size_t i = 0; i < N; ++i) { v[i] = n; } } template -void print(const Vector& v, char delimiter, std::ostream& stream) { +void Print(const Vector& v, char delimiter, std::ostream& stream) { stream << v[0]; for (size_t i = 1; i < N; ++i) { stream << delimiter << v[i]; @@ -96,7 +96,7 @@ const Vector operator*(const T& lhs, const Vector& rhs) { } template -const T inner_product(const Vector& lhs, const Vector& rhs) { +const T InnerProduct(const Vector& lhs, const Vector& rhs) { T temp = 0; for (size_t i = 0; i < N; ++i) { temp += lhs[i] * rhs[i]; @@ -105,7 +105,7 @@ const T inner_product(const Vector& lhs, const Vector& rhs) { } template -const Vector<3, T> outer_product(const Vector<3, T>& lhs, const Vector<3, T>& rhs) { +const Vector<3, T> OuterProduct(const Vector<3, T>& lhs, const Vector<3, T>& rhs) { Vector<3, T> temp; temp[0] = lhs[1] * rhs[2] - lhs[2] * rhs[1]; temp[1] = lhs[2] * rhs[0] - lhs[0] * rhs[2]; @@ -114,7 +114,7 @@ const Vector<3, T> outer_product(const Vector<3, T>& lhs, const Vector<3, T>& rh } template -double norm(const Vector& v) { +double CalcNorm(const Vector& v) { double temp = 0.0; for (size_t i = 0; i < N; ++i) { temp += pow(v[i], 2.0); @@ -123,8 +123,8 @@ double norm(const Vector& v) { } template -Vector& normalize(Vector& v) { - double n = norm(v); +Vector& Normalize(Vector& v) { + double n = CalcNorm(v); if (n == 0.0) { return v; } // 零ベクトル @@ -139,8 +139,8 @@ Vector& normalize(Vector& v) { } template -double angle(const Vector& v1, const Vector& v2) { - double cos = inner_product(v1, v2) / (norm(v1) * norm(v2)); +double CalcAngleTwoVectors_rad(const Vector& v1, const Vector& v2) { + double cos = InnerProduct(v1, v2) / (CalcNorm(v1) * CalcNorm(v2)); return acos(cos); } diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index d49df014f..fccf60c46 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -33,18 +33,18 @@ OrbitalElements::~OrbitalElements() {} void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s) { // common variables - double r_m = norm(position_i_m); - double v2_m2_s2 = inner_product(velocity_i_m_s, velocity_i_m_s); + double r_m = CalcNorm(position_i_m); + double v2_m2_s2 = InnerProduct(velocity_i_m_s, velocity_i_m_s); libra::Vector<3> h; //!< angular momentum vector - h = outer_product(position_i_m, velocity_i_m_s); - double h_norm = norm(h); + h = OuterProduct(position_i_m, velocity_i_m_s); + double h_norm = CalcNorm(h); // semi major axis semi_major_axis_m_ = mu_m3_s2 / (2.0 * mu_m3_s2 / r_m - v2_m2_s2); // inclination libra::Vector<3> h_direction = h; - h_direction = normalize(h_direction); + h_direction = Normalize(h_direction); inclination_rad_ = acos(h_direction[2]); // RAAN diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 38229e578..31ec14617 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -55,7 +55,7 @@ bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { Quaternion q_ecef_to_ltc = gs_position_geo_.GetQuaternionXcxfToLtc(); Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] - normalize(sc_pos_ltc); + Normalize(sc_pos_ltc); Vector<3> dir_gs_to_zenith = Vector<3>(0); dir_gs_to_zenith[2] = 1; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 7a014c6c4..ed4dcde0f 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -189,17 +189,17 @@ void InitParameter::gen_SphericalNormalUniformUniform() { void InitParameter::get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] Vector<3> mean_vec_dir; - mean_vec_dir = 1.0 / norm(mean_vec) * mean_vec; // Unit vector of mean vector direction + mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction Vector<3> x_axis(0.0), y_axis(0.0); x_axis[0] = 1.0; y_axis[1] = 1.0; - Vector<3> op_x = outer_product(mean_vec_dir, x_axis); - Vector<3> op_y = outer_product(mean_vec_dir, y_axis); + Vector<3> op_x = OuterProduct(mean_vec_dir, x_axis); + Vector<3> op_y = OuterProduct(mean_vec_dir, y_axis); // An unit vector perpendicular with the mean vector // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product - Vector<3> normal_unit_vec = norm(op_x) > norm(op_y) ? normalize(op_x) : normalize(op_y); + Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); double rotation_angle_of_normal_unit_vec = InitParameter::Uniform_1d(0.0, libra::tau); Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) @@ -209,7 +209,7 @@ void InitParameter::get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& m Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction - ret_vec = InitParameter::Normal_1d(norm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm + ret_vec = InitParameter::Normal_1d(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { dst[i] = ret_vec[i]; @@ -247,8 +247,8 @@ void InitParameter::get_QuaternionUniform(Quaternion& dst) { x_axis_cnvd[1] = sin(theta) * sin(phi); x_axis_cnvd[2] = cos(theta); - double cos_angle_between = inner_product(x_axis, x_axis_cnvd); - Vector<3> op = outer_product(x_axis, x_axis_cnvd); + double cos_angle_between = InnerProduct(x_axis, x_axis_cnvd); + Vector<3> op = OuterProduct(x_axis, x_axis_cnvd); for (int i = 0; i < 3; i++) { first_cnv[i] = op[i]; } diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 188a15381..33aa4c247 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -19,7 +19,7 @@ void RelativeInformation::Update() { rel_pos_list_rtn_m_[target_sat_id][reference_sat_id] = CalcRelativePosition_rtn_m(target_sat_id, reference_sat_id); // Distance - rel_distance_list_m_[target_sat_id][reference_sat_id] = norm(rel_pos_list_i_m_[target_sat_id][reference_sat_id]); + rel_distance_list_m_[target_sat_id][reference_sat_id] = CalcNorm(rel_pos_list_i_m_[target_sat_id][reference_sat_id]); // Velocity libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); @@ -138,7 +138,7 @@ libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int tar libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> rot_vec_rtn_i = cross(reference_sat_pos_i, reference_sat_vel_i); - double r2_ref = norm(reference_sat_pos_i) * norm(reference_sat_pos_i); + double r2_ref = CalcNorm(reference_sat_pos_i) * CalcNorm(reference_sat_pos_i); rot_vec_rtn_i /= r2_ref; libra::Vector<3> relative_vel_i = target_sat_vel_i - reference_sat_vel_i - cross(rot_vec_rtn_i, relative_pos_i); diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index a7fe90bd7..b2e2c79af 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -93,11 +93,11 @@ vector InitSurfaces(std::string ini_path) { keyword = "normal_vector" + idx + "_b"; conf.ReadVector(section, keyword.c_str(), normal); - if (norm(normal) > 1.0 + MIN_VAL) // Fixme: magic word + if (CalcNorm(normal) > 1.0 + MIN_VAL) // Fixme: magic word { cout << "Surface Warning! " << keyword << ": norm is larger than 1.0."; cout << "The vector is normalized.\n"; - normal = normalize(normal); + normal = Normalize(normal); } // Add a surface diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 2f15cba07..87821cd99 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -72,7 +72,7 @@ class Surface { */ inline void SetNormal_b(const Vector<3> normal_b) { normal_ = normal_b; - normal_ = normalize(normal_); + normal_ = Normalize(normal_); } /** * @fn SetArea From 31d68614a41847aab6aa093e9e595efc26873b08 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 20:59:28 +0100 Subject: [PATCH 0710/1086] Remove unnecessary public function --- src/library/math/vector.hpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 982f6efb2..3d351209e 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -235,15 +235,6 @@ double CalcAngleTwoVectors_rad(const Vector& v1, const Vector ConvertFrameOrthogonal2Polar(const Vector<3, double>& ortho); -/** - * @fn ortho2lonlat - * @brief Convert orthogonal coordinate (x, y, z) to Geodetic coordinate (altitude, latitude, longitude) - * @note TODO: Consider merge with GeodeticPosition class - * @param [in] ortho: Vector in orthogonal coordinate - * @return Vector in Geodetic coordinate - */ -Vector<3, double> ortho2lonlat(const Vector<3, double>& ortho); - /** * @fn GenerateOrthogonalUnitVector * @brief Generate one unit vector orthogonal to the given 3D vector From bb771fdbfb9276ad550f8e3c2c766457c55625bb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:04:24 +0100 Subject: [PATCH 0711/1086] Fix local function variables --- src/library/math/vector.cpp | 78 ++++++++++++++----------------------- src/library/math/vector.hpp | 4 +- 2 files changed, 32 insertions(+), 50 deletions(-) diff --git a/src/library/math/vector.cpp b/src/library/math/vector.cpp index c9173869c..cbfd5e54a 100644 --- a/src/library/math/vector.cpp +++ b/src/library/math/vector.cpp @@ -8,65 +8,47 @@ #include "constants.hpp" namespace libra { -Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& ortho) { - Vector<3, double> spher; // vector on the polar coordinate - FillUp(spher, 0.0); - spher[0] = CalcNorm(ortho); +Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& orthogonal) { + Vector<3, double> polar; // vector on the polar coordinate + FillUp(polar, 0.0); + polar[0] = CalcNorm(orthogonal); // Skip when zero vector - if (spher[0] == 0.0) { - return spher; + if (polar[0] == 0.0) { + return polar; } - spher[1] = acos(ortho[2] / spher[0]); - // Skip phi calculation when the ortho is on the Z-axis - if ((ortho[0] == 0.0) && (ortho[1] == 0.0)) { - return spher; + polar[1] = acos(orthogonal[2] / polar[0]); + // Skip phi calculation when the orthogonal is on the Z-axis + if ((orthogonal[0] == 0.0) && (orthogonal[1] == 0.0)) { + return polar; } - spher[2] = atan2(ortho[1], ortho[0]); - if (spher[2] < 0.0) { - spher[2] += numbers::tau; + polar[2] = atan2(orthogonal[1], orthogonal[0]); + if (polar[2] < 0.0) { + polar[2] += numbers::tau; } - return spher; -} - -Vector<3, double> ortho2lonlat(const Vector<3, double>& ortho) { - Vector<3, double> lonlat; - FillUp(lonlat, 0.0); - lonlat[0] = CalcNorm(ortho); - // Skip when zero vector - if (lonlat[0] == 0.0) { - return lonlat; - } - lonlat[1] = numbers::pi_2 - acos(ortho[2] / lonlat[0]); - // Skip phi calculation when the ortho is on the Z-axis - if ((ortho[0] == 0.0) && (ortho[1] == 0.0)) { - return lonlat; - } - lonlat[2] = atan2(ortho[1], ortho[0]); - - return lonlat; + return polar; } Vector<3, double> GenerateOrthogonalUnitVector(const Vector<3, double>& v) { - Vector<3> v_ortho; + Vector<3> orthogonal_vector; if (v[0] * v[0] <= v[1] * v[1] && v[0] * v[0] <= v[1] * v[1]) { - v_ortho[0] = 0.0; - v_ortho[1] = v[2]; - v_ortho[2] = -v[1]; - v_ortho = Normalize(v_ortho); - return (v_ortho); + orthogonal_vector[0] = 0.0; + orthogonal_vector[1] = v[2]; + orthogonal_vector[2] = -v[1]; + orthogonal_vector = Normalize(orthogonal_vector); + return (orthogonal_vector); } else if (v[1] * v[1] <= v[0] * v[0] && v[1] * v[1] <= v[2] * v[2]) { - v_ortho[0] = -v[2]; - v_ortho[1] = 0.0; - v_ortho[2] = v[0]; - v_ortho = Normalize(v_ortho); - return (v_ortho); + orthogonal_vector[0] = -v[2]; + orthogonal_vector[1] = 0.0; + orthogonal_vector[2] = v[0]; + orthogonal_vector = Normalize(orthogonal_vector); + return (orthogonal_vector); } else { - v_ortho[0] = v[1]; - v_ortho[1] = -v[0]; - v_ortho[2] = 0.0; - v_ortho = Normalize(v_ortho); - return (v_ortho); + orthogonal_vector[0] = v[1]; + orthogonal_vector[1] = -v[0]; + orthogonal_vector[2] = 0.0; + orthogonal_vector = Normalize(orthogonal_vector); + return (orthogonal_vector); } } } // namespace libra diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 3d351209e..f6ee24c43 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -230,10 +230,10 @@ double CalcAngleTwoVectors_rad(const Vector& v1, const Vector ConvertFrameOrthogonal2Polar(const Vector<3, double>& ortho); +Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& orthogonal); /** * @fn GenerateOrthogonalUnitVector From 423f995d49fbd93c6e3acc15b9e85a93b137dfeb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:05:16 +0100 Subject: [PATCH 0712/1086] Delete Japanese comments --- src/library/math/vector_template_functions.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index 9079f6f70..9a41219dc 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -127,9 +127,8 @@ Vector& Normalize(Vector& v) { double n = CalcNorm(v); if (n == 0.0) { return v; - } // 零ベクトル + } - // 正規化 n = 1.0 / n; for (size_t i = 0; i < N; ++i) { v[i] *= n; From 8502f9942fa33f94e103122b42207662b5626ee2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:09:22 +0100 Subject: [PATCH 0713/1086] Move inline functions --- src/library/math/quaternion.hpp | 24 ++++++++++------- .../math/quaternion_inline_functions.hpp | 26 +------------------ 2 files changed, 16 insertions(+), 34 deletions(-) diff --git a/src/library/math/quaternion.hpp b/src/library/math/quaternion.hpp index f340368b1..e49722e64 100644 --- a/src/library/math/quaternion.hpp +++ b/src/library/math/quaternion.hpp @@ -21,7 +21,7 @@ class Quaternion { * @fn Quaternion * @brief Default constructor without any initialization */ - inline Quaternion(); + inline Quaternion() {} /** * @fn Quaternion * @brief Constructor with initialization @@ -30,13 +30,18 @@ class Quaternion { * @param [in] quaternion_z: The third element of Quaternion (Z) * @param [in] quaternion_w: The fourth element of Quaternion (W) */ - inline Quaternion(const double quaternion_x, const double quaternion_y, const double quaternion_z, const double quaternion_w); + inline Quaternion(const double quaternion_x, const double quaternion_y, const double quaternion_z, const double quaternion_w) { + quaternion_[0] = quaternion_x; + quaternion_[1] = quaternion_y; + quaternion_[2] = quaternion_z; + quaternion_[3] = quaternion_w; + } /** * @fn Quaternion * @brief Constructor initialized with vector * @param [in] quaternion_vector: Vector storing quaternion */ - inline Quaternion(const Vector<4>& quaternion_vector); + inline Quaternion(const Vector<4>& quaternion_vector) : quaternion_(quaternion_vector) {} /** * @fn Quaternion * @brief Constructor initialized with rotation expression @@ -58,7 +63,10 @@ class Quaternion { * @param [in] quaternion_vector: Vector * @return Quaternion */ - inline Quaternion& operator=(const Vector<4>& quaternion_vector); + inline Quaternion& operator=(const Vector<4>& quaternion_vector) { + quaternion_ = quaternion_vector; + return *this; + } /** * @fn Cast operator to const Vector<4> @@ -66,19 +74,19 @@ class Quaternion { * @note Users can use Quaternion as Vector<4> object * @return Const reference to the internal Vector<4> */ - inline operator const Vector<4>&() const; + inline operator const Vector<4>&() const { return quaternion_; } /** * @fn Cast operator * @brief Operator to directly access the element like array with [] operator */ - inline operator double*(); + inline operator double*() { return quaternion_; } /** * @fn Cast operator (const ver.) * @brief Operator to directly access the element like array with [] operator */ - inline operator const double*() const; + inline operator const double*() const { return quaternion_; } /** * @fn Normalize @@ -197,6 +205,4 @@ Quaternion operator*(const Quaternion& lhs, const Vector<3>& rhs); Quaternion operator*(const double& lhs, const Quaternion& rhs); } // namespace libra -#include "quaternion_inline_functions.hpp" - #endif // S2E_LIBRARY_MATH_QUATERNION_HPP_ diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp index b039cf0be..1149b83ae 100644 --- a/src/library/math/quaternion_inline_functions.hpp +++ b/src/library/math/quaternion_inline_functions.hpp @@ -6,30 +6,6 @@ #ifndef S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ #define S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ -namespace libra { - -Quaternion::Quaternion() {} - -Quaternion::Quaternion(const double quaternion_x, const double quaternion_y, const double quaternion_z, const double quaternion_w) { - quaternion_[0] = quaternion_x; - quaternion_[1] = quaternion_y; - quaternion_[2] = quaternion_z; - quaternion_[3] = quaternion_w; -} - -Quaternion::Quaternion(const Vector<4>& quaternion_vector) : quaternion_(quaternion_vector) {} - -Quaternion& Quaternion::operator=(const Vector<4>& quaternion_vector) { - quaternion_ = quaternion_vector; - return *this; -} - -Quaternion::operator double*() { return quaternion_; } - -Quaternion::operator const double*() const { return quaternion_; } - -Quaternion::operator const Vector<4>&() const { return quaternion_; } - -} // namespace libra +namespace libra {} // namespace libra #endif // S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ From 5662f3d243e6eee054a65182e42b4d8c00c88f0f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:09:58 +0100 Subject: [PATCH 0714/1086] Delete unnecessary file --- src/library/math/quaternion_inline_functions.hpp | 11 ----------- 1 file changed, 11 deletions(-) delete mode 100644 src/library/math/quaternion_inline_functions.hpp diff --git a/src/library/math/quaternion_inline_functions.hpp b/src/library/math/quaternion_inline_functions.hpp deleted file mode 100644 index 1149b83ae..000000000 --- a/src/library/math/quaternion_inline_functions.hpp +++ /dev/null @@ -1,11 +0,0 @@ -/** - * @file quaternion_inline_functions.hpp - * @brief Class for Quaternion (Inline functions) - */ - -#ifndef S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ -#define S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ - -namespace libra {} // namespace libra - -#endif // S2E_LIBRARY_MATH_QUATERNION_INLINE_FUNCTIONS_HPP_ From c0d1a9a4f70098d1db8f379f0a5bc31f369bd87d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:11:42 +0100 Subject: [PATCH 0715/1086] Fix argument name --- src/library/math/s2e_math.cpp | 4 ++-- src/library/math/s2e_math.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/library/math/s2e_math.cpp b/src/library/math/s2e_math.cpp index df2108040..4ed37a10e 100644 --- a/src/library/math/s2e_math.cpp +++ b/src/library/math/s2e_math.cpp @@ -8,8 +8,8 @@ #include namespace libra { -double WrapTo2Pi(const double angle) { - double angle_out = angle; +double WrapTo2Pi(const double angle_rad) { + double angle_out = angle_rad; if (angle_out < 0.0) { while (angle_out < 0.0) { angle_out += libra::tau; diff --git a/src/library/math/s2e_math.hpp b/src/library/math/s2e_math.hpp index 175f2072d..b2095ad21 100644 --- a/src/library/math/s2e_math.hpp +++ b/src/library/math/s2e_math.hpp @@ -13,9 +13,9 @@ namespace libra { /** * @fn WrapTo2Pi * @brief Wrap angle value into [0, 2pi] - * @param angle: Angle [rad] + * @param angle_rad: Angle [rad] */ -double WrapTo2Pi(const double angle); +double WrapTo2Pi(const double angle_rad); } // namespace libra From 5eab01f1def98a61c371967198f8919876e27c79 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:21:04 +0100 Subject: [PATCH 0716/1086] Fix format --- src/components/real/mission/telescope.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 84d4146ec..6535c53e0 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -74,7 +74,8 @@ void Telescope::MainRoutine(int count) { // earth_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); // moon_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); // angle_sun = CalcAngleTwoVectors_rad(sight_, sun_pos_c) * 180/libra::pi; - // angle_earth = CalcAngleTwoVectors_rad(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = CalcAngleTwoVectors_rad(sight_, moon_pos_c) * 180 / libra::pi; + // angle_earth = CalcAngleTwoVectors_rad(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = CalcAngleTwoVectors_rad(sight_, moon_pos_c) * 180 / + // libra::pi; //****************************************************************************** } From 27d6edc08d4ae1e107a8cf6c8d87bfbc5233611a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:28:00 +0100 Subject: [PATCH 0717/1086] Revert external library codes --- src/library/external/inih/cpp/INIReader.cpp | 4 ++-- src/library/external/inih/cpp/INIReader.h | 2 +- src/library/external/sgp4/sgp4ext.cpp | 8 ++++---- src/library/external/sgp4/sgp4ext.h | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/library/external/inih/cpp/INIReader.cpp b/src/library/external/inih/cpp/INIReader.cpp index 1e8099105..87743d226 100644 --- a/src/library/external/inih/cpp/INIReader.cpp +++ b/src/library/external/inih/cpp/INIReader.cpp @@ -21,8 +21,8 @@ using std::string; INIReader::INIReader(const string& filename) { _error = ini_parse(filename.c_str(), ValueHandler, this); } -INIReader::INIReader(const char* buffer, size_t buffer_size_) { - string content(buffer, buffer_size_); +INIReader::INIReader(const char* buffer, size_t buffer_size) { + string content(buffer, buffer_size); _error = ini_parse_string(content.c_str(), ValueHandler, this); } diff --git a/src/library/external/inih/cpp/INIReader.h b/src/library/external/inih/cpp/INIReader.h index da51ff62b..d4c23eb4f 100644 --- a/src/library/external/inih/cpp/INIReader.h +++ b/src/library/external/inih/cpp/INIReader.h @@ -25,7 +25,7 @@ class INIReader { // Construct INIReader and parse given buffer. See ini.h for more info // about the parsing. - explicit INIReader(const char* buffer, size_t buffer_size_); + explicit INIReader(const char* buffer, size_t buffer_size); // Return the result of ini_parse(), i.e., 0 on success, line number of // first error on parse error, or -1 on file open error. diff --git a/src/library/external/sgp4/sgp4ext.cpp b/src/library/external/sgp4/sgp4ext.cpp index 8fffa39e1..593a93c21 100644 --- a/src/library/external/sgp4/sgp4ext.cpp +++ b/src/library/external/sgp4/sgp4ext.cpp @@ -241,7 +241,7 @@ double dot(double x[3], double y[3]) { return (x[0] * y[0] + x[1] * y[1] + x[2] * --------------------------------------------------------------------------- */ -double CalcAngleTwoVectors_rad(double vec1[3], double vec2[3]) { +double angle(double vec1[3], double vec2[3]) { double small, undefined, magv1, magv2, temp; small = 0.00000001; undefined = 999999.1; @@ -492,14 +492,14 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e // ---------------- find argument of perigee --------------- if (strcmp(typeorbit, "ei") == 0) { - argp = CalcAngleTwoVectors_rad(nbar, ebar); + argp = angle(nbar, ebar); if (ebar[2] < 0.0) argp = twopi - argp; } else argp = undefined; // ------------ find true anomaly at epoch ------------- if (typeorbit[0] == 'e') { - nu = CalcAngleTwoVectors_rad(ebar, r); + nu = angle(ebar, r); if (rdotv < 0.0) nu = twopi - nu; } else nu = undefined; @@ -507,7 +507,7 @@ void rv2coe(double r[3], double v[3], double mu, double& p, double& a, double& e // ---- find argument of latitude - circular inclined ----- // 緯度の計算(円の/傾斜面の) if (strcmp(typeorbit, "ci") == 0) { - arglat = CalcAngleTwoVectors_rad(nbar, r); + arglat = angle(nbar, r); if (r[2] < 0.0) arglat = twopi - arglat; m = arglat; } else diff --git a/src/library/external/sgp4/sgp4ext.h b/src/library/external/sgp4/sgp4ext.h index 2ebb3fa55..a46d3fcfa 100644 --- a/src/library/external/sgp4/sgp4ext.h +++ b/src/library/external/sgp4/sgp4ext.h @@ -40,7 +40,7 @@ void cross(double[], double[], double[]); double dot(double[], double[]); -double CalcAngleTwoVectors_rad(double[], double[]); +double angle(double[], double[]); void newtonnu(double ecc, double nu, double& e0, double& m); From 997158a7ae581e70c0b39eab483572dd01d32d44 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 21:49:55 +0100 Subject: [PATCH 0718/1086] Fix mu to gravity_constant --- src/library/orbit/kepler_orbit.cpp | 6 ++++-- src/library/orbit/kepler_orbit.hpp | 6 +++--- src/library/orbit/orbital_elements.cpp | 14 +++++++------- src/library/orbit/orbital_elements.hpp | 8 ++++---- src/library/orbit/relative_orbit_models.cpp | 8 ++++---- src/library/orbit/relative_orbit_models.hpp | 8 ++++---- 6 files changed, 26 insertions(+), 24 deletions(-) diff --git a/src/library/orbit/kepler_orbit.cpp b/src/library/orbit/kepler_orbit.cpp index 8f6e68d29..4c2714925 100644 --- a/src/library/orbit/kepler_orbit.cpp +++ b/src/library/orbit/kepler_orbit.cpp @@ -9,7 +9,9 @@ KeplerOrbit::KeplerOrbit() {} // Initialize with orbital elements -KeplerOrbit::KeplerOrbit(const double mu_m3_s2, const OrbitalElements oe) : mu_m3_s2_(mu_m3_s2), oe_(oe) { CalcConstKeplerMotion(); } +KeplerOrbit::KeplerOrbit(const double gravity_constant_m3_s2, const OrbitalElements oe) : gravity_constant_m3_s2_(gravity_constant_m3_s2), oe_(oe) { + CalcConstKeplerMotion(); +} KeplerOrbit::~KeplerOrbit() {} @@ -17,7 +19,7 @@ KeplerOrbit::~KeplerOrbit() {} void KeplerOrbit::CalcConstKeplerMotion() { // mean motion double a_m3 = pow(oe_.GetSemiMajorAxis_m(), 3.0); - mean_motion_rad_s_ = sqrt(mu_m3_s2_ / a_m3); + mean_motion_rad_s_ = sqrt(gravity_constant_m3_s2_ / a_m3); // DCM libra::Matrix<3, 3> dcm_arg_perigee = libra::MakeRotationMatrixZ(-1.0 * oe_.GetArgPerigee_rad()); diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 3df7a80ac..80beca330 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -24,10 +24,10 @@ class KeplerOrbit { /** * @fn KeplerOrbit * @brief Constructor - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] oe: Orbital elements */ - KeplerOrbit(const double mu_m3_s2, const OrbitalElements oe); + KeplerOrbit(const double gravity_constant_m3_s2, const OrbitalElements oe); /** * @fn ~KeplerOrbit * @brief Destructor @@ -57,7 +57,7 @@ class KeplerOrbit { libra::Vector<3> velocity_i_m_s_; //!< Velocity vector in the inertial frame [m/s] private: - double mu_m3_s2_; //!< Gravity constant of the center body [m3/s2] + double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] OrbitalElements oe_; //!< Orbital elements double mean_motion_rad_s_; //!< Mean motion of the orbit [rad/s] libra::Matrix<3, 3> dcm_inplane_to_i_; //!< Direction cosine matrix from the in-plane frame to the inertial frame diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index fccf60c46..5bc32b105 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -22,15 +22,15 @@ OrbitalElements::OrbitalElements(const double epoch_jday, const double semi_majo epoch_jday_(epoch_jday) {} // initialize with position and velocity -OrbitalElements::OrbitalElements(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, +OrbitalElements::OrbitalElements(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s) { - CalcOeFromPosVel(mu_m3_s2, time_jday, position_i_m, velocity_i_m_s); + CalcOeFromPosVel(gravity_constant_m3_s2, time_jday, position_i_m, velocity_i_m_s); } OrbitalElements::~OrbitalElements() {} // Private Function -void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, +void OrbitalElements::CalcOeFromPosVel(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s) { // common variables double r_m = CalcNorm(position_i_m); @@ -40,7 +40,7 @@ void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_ double h_norm = CalcNorm(h); // semi major axis - semi_major_axis_m_ = mu_m3_s2 / (2.0 * mu_m3_s2 / r_m - v2_m2_s2); + semi_major_axis_m_ = gravity_constant_m3_s2 / (2.0 * gravity_constant_m3_s2 / r_m - v2_m2_s2); // inclination libra::Vector<3> h_direction = h; @@ -66,8 +66,8 @@ void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_ double dy_p_m_s = dtmp_m_s * cos(inclination_rad_) + velocity_i_m_s[2] * sin(inclination_rad_); // eccentricity - double t1 = (h_norm / mu_m3_s2) * dy_p_m_s - x_p_m / r_m; - double t2 = -(h_norm / mu_m3_s2) * dx_p_m_s - y_p_m / r_m; + double t1 = (h_norm / gravity_constant_m3_s2) * dy_p_m_s - x_p_m / r_m; + double t2 = -(h_norm / gravity_constant_m3_s2) * dx_p_m_s - y_p_m / r_m; eccentricity_ = sqrt(t1 * t1 + t2 * t2); // arg perigee @@ -82,7 +82,7 @@ void OrbitalElements::CalcOeFromPosVel(const double mu_m3_s2, const double time_ u_rad = libra::WrapTo2Pi(u_rad); // epoch t0 - double n_rad_s = sqrt(mu_m3_s2 / pow(semi_major_axis_m_, 3.0)); + double n_rad_s = sqrt(gravity_constant_m3_s2 / pow(semi_major_axis_m_, 3.0)); double dt_s = (u_rad - eccentricity_ * sin(u_rad)) / n_rad_s; epoch_jday_ = time_jday - dt_s / (24.0 * 60.0 * 60.0); } diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index 1ac4cb591..194c59b9d 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -34,12 +34,12 @@ class OrbitalElements { /** * @fn OrbitalElements * @brief Constructor: Initialize with position and velocity - * @param[in] mu_m3_s2: Gravity constant [m3/s2] + * @param[in] gravity_constant_m3_s2: Gravity constant [m3/s2] * @param[in] time_jday: Time expressed as Julian day * @param[in] position_i_m: Position vector in the inertial frame [m] * @param[in] velocity_i_m_s: Velocity vector in the inertial frame [m/s] */ - OrbitalElements(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); + OrbitalElements(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); /** * @fn ~OrbitalElements * @brief Destructor @@ -94,12 +94,12 @@ class OrbitalElements { /** * @fn CalcOeFromPosVel * @brief Calculation of Orbital Elements from Position and Velocity - * @param[in] mu_m3_s2: Gravity Constant of the center body + * @param[in] gravity_constant_m3_s2: Gravity Constant of the center body * @param[in] time_jday: Time expressed as Julian day * @param[in] position_i_m: Position vector in the inertial frame [m] * @param[in] velocity_i_m_s: Velocity vector in the inertial frame [m/s] */ - void CalcOeFromPosVel(const double mu_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); + void CalcOeFromPosVel(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); }; #endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ diff --git a/src/library/orbit/relative_orbit_models.cpp b/src/library/orbit/relative_orbit_models.cpp index ae78641e5..95263cd93 100644 --- a/src/library/orbit/relative_orbit_models.cpp +++ b/src/library/orbit/relative_orbit_models.cpp @@ -4,10 +4,10 @@ */ #include "relative_orbit_models.hpp" -libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius_m, double mu_m3_s2) { +libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius_m, double gravity_constant_m3_s2) { libra::Matrix<6, 6> system_matrix; - double n = sqrt(mu_m3_s2 / pow(orbit_radius_m, 3)); + double n = sqrt(gravity_constant_m3_s2 / pow(orbit_radius_m, 3)); system_matrix[0][0] = 0.0; system_matrix[0][1] = 0.0; system_matrix[0][2] = 0.0; @@ -48,10 +48,10 @@ libra::Matrix<6, 6> CalcHillSystemMatrix(double orbit_radius_m, double mu_m3_s2) return system_matrix; } -libra::Matrix<6, 6> CalcHcwStm(double orbit_radius_m, double mu_m3_s2, double elapsed_time_s) { +libra::Matrix<6, 6> CalcHcwStm(double orbit_radius_m, double gravity_constant_m3_s2, double elapsed_time_s) { libra::Matrix<6, 6> stm; - double n = sqrt(mu_m3_s2 / pow(orbit_radius_m, 3)); + double n = sqrt(gravity_constant_m3_s2 / pow(orbit_radius_m, 3)); double t = elapsed_time_s; stm[0][0] = 4.0 - 3.0 * cos(n * t); stm[0][1] = 0.0; diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index 71eb9ce23..c974ac45c 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -26,20 +26,20 @@ enum class StmModel { HCW = 0 }; * @fn CalcHillSystemMatrix * @brief Calculate Hill System Matrix * @param [in] orbit_radius_m: Orbit radius [m] - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @return System matrix */ -libra::Matrix<6, 6> CalcHillSystemMatrix(const double orbit_radius_m, const double mu_m3_s2); +libra::Matrix<6, 6> CalcHillSystemMatrix(const double orbit_radius_m, const double gravity_constant_m3_s2); // STMs /** * @fn CalcHcwStm * @brief Calculate HCW State Transition Matrix * @param [in] orbit_radius_m: Orbit radius [m] - * @param [in] mu_m3_s2: Gravity constant of the center body [m3/s2] + * @param [in] gravity_constant_m3_s2: Gravity constant of the center body [m3/s2] * @param [in] elapsed_time_s: Elapsed time [s] * @return State Transition Matrix */ -libra::Matrix<6, 6> CalcHcwStm(const double orbit_radius_m, const double mu_m3_s2, const double elapsed_time_s); +libra::Matrix<6, 6> CalcHcwStm(const double orbit_radius_m, const double gravity_constant_m3_s2, const double elapsed_time_s); #endif // S2E_LIBRARY_ORBIT_RELATIVE_ORBIT_MODEL_HPP_ From c208a779827cf90fa858ab5f0e78947dd3157a97 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:07:01 +0100 Subject: [PATCH 0719/1086] Fix format --- src/library/orbit/kepler_orbit.hpp | 2 +- src/library/orbit/orbital_elements.hpp | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/library/orbit/kepler_orbit.hpp b/src/library/orbit/kepler_orbit.hpp index 80beca330..0d83142eb 100644 --- a/src/library/orbit/kepler_orbit.hpp +++ b/src/library/orbit/kepler_orbit.hpp @@ -57,7 +57,7 @@ class KeplerOrbit { libra::Vector<3> velocity_i_m_s_; //!< Velocity vector in the inertial frame [m/s] private: - double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] + double gravity_constant_m3_s2_; //!< Gravity constant of the center body [m3/s2] OrbitalElements oe_; //!< Orbital elements double mean_motion_rad_s_; //!< Mean motion of the orbit [rad/s] libra::Matrix<3, 3> dcm_inplane_to_i_; //!< Direction cosine matrix from the in-plane frame to the inertial frame diff --git a/src/library/orbit/orbital_elements.hpp b/src/library/orbit/orbital_elements.hpp index 194c59b9d..ca38435a1 100644 --- a/src/library/orbit/orbital_elements.hpp +++ b/src/library/orbit/orbital_elements.hpp @@ -39,7 +39,8 @@ class OrbitalElements { * @param[in] position_i_m: Position vector in the inertial frame [m] * @param[in] velocity_i_m_s: Velocity vector in the inertial frame [m/s] */ - OrbitalElements(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); + OrbitalElements(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, + const libra::Vector<3> velocity_i_m_s); /** * @fn ~OrbitalElements * @brief Destructor @@ -99,7 +100,8 @@ class OrbitalElements { * @param[in] position_i_m: Position vector in the inertial frame [m] * @param[in] velocity_i_m_s: Velocity vector in the inertial frame [m/s] */ - void CalcOeFromPosVel(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s); + void CalcOeFromPosVel(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, + const libra::Vector<3> velocity_i_m_s); }; #endif // S2E_LIBRARY_ORBIT_ORBITAL_ELEMENTS_HPP_ From 582cfe59cab154efc024ce32496f00320748351c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:10:50 +0100 Subject: [PATCH 0720/1086] Fix for Windows Visual Studio build --- src/library/initialize/initialize_file_access.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/library/initialize/initialize_file_access.cpp b/src/library/initialize/initialize_file_access.cpp index 22a2dbbbe..f47196e05 100644 --- a/src/library/initialize/initialize_file_access.cpp +++ b/src/library/initialize/initialize_file_access.cpp @@ -35,14 +35,14 @@ IniAccess::IniAccess(const std::string file_path) : file_path_(file_path), ini_r double IniAccess::ReadDouble(const char* section_name, const char* key_name) { #ifdef WIN32 - stringstream value; + std::stringstream value; double temp = 0; GetPrivateProfileStringA(section_name, key_name, 0, text_buffer_, kMaxCharLength, file_path_char_); value << text_buffer_; // input string value >> temp; // return as double - // cout << text_buffer_; + // std::cout << text_buffer_; return temp; #else @@ -120,7 +120,7 @@ std::string IniAccess::ReadString(const char* section_name, const char* key_name #ifdef WIN32 char temp[kMaxCharLength]; ReadChar(section_name, key_name, kMaxCharLength, temp); - return string(temp); + return std::string(temp); #else std::string value = ini_reader_.GetString(section_name, key_name, "NULL"); return value; From f877df5098602608ae07bcc27eaf5b689f6d146c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:36:02 +0100 Subject: [PATCH 0721/1086] Fix private variables --- src/components/base/component.cpp | 14 +++++++------- src/components/base/component.hpp | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index 68957ef96..bfe0195e3 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -5,16 +5,16 @@ #include "component.hpp" -ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler) : clock_gen_(clock_gen) { +ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler) : clock_generator_(clock_gen) { power_port_ = new PowerPort(); - clock_gen_->RegisterComponent(this); + clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, int fast_prescaler) - : clock_gen_(clock_gen), power_port_(power_port) { - clock_gen_->RegisterComponent(this); + : clock_generator_(clock_gen), power_port_(power_port) { + clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } @@ -23,12 +23,12 @@ ComponentBase::ComponentBase(const ComponentBase& obj) { prescaler_ = obj.prescaler_; fast_prescaler_ = obj.fast_prescaler_; needs_fast_update_ = obj.needs_fast_update_; - clock_gen_ = obj.clock_gen_; - clock_gen_->RegisterComponent(this); + clock_generator_ = obj.clock_generator_; + clock_generator_->RegisterComponent(this); power_port_ = obj.power_port_; } -ComponentBase::~ComponentBase() { clock_gen_->RemoveComponent(this); } +ComponentBase::~ComponentBase() { clock_generator_->RemoveComponent(this); } void ComponentBase::Tick(int count) { if (count % prescaler_ > 0) return; diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 2c1aabf3e..6f8428e7f 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -84,8 +84,8 @@ class ComponentBase : public ITickable { */ virtual void PowerOffRoutine(){}; - ClockGenerator* clock_gen_; //!< Clock generator - PowerPort* power_port_; //!< Power port + ClockGenerator* clock_generator_; //!< Clock generator + PowerPort* power_port_; //!< Power port }; #endif // S2E_COMPONENTS_BASE_COMPONENT_HPP_ From 73d8967ced3e0d5b64985e43661e4e3c57400a93 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:39:25 +0100 Subject: [PATCH 0722/1086] Add const to function arguments --- src/components/base/component.cpp | 8 ++++---- src/components/base/component.hpp | 12 ++++++------ 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index bfe0195e3..e5b83b7cf 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -5,14 +5,14 @@ #include "component.hpp" -ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler) : clock_generator_(clock_gen) { +ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_gen, const int fast_prescaler) : clock_generator_(clock_gen) { power_port_ = new PowerPort(); clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, int fast_prescaler) +ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int fast_prescaler) : clock_generator_(clock_gen), power_port_(power_port) { clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; @@ -30,7 +30,7 @@ ComponentBase::ComponentBase(const ComponentBase& obj) { ComponentBase::~ComponentBase() { clock_generator_->RemoveComponent(this); } -void ComponentBase::Tick(int count) { +void ComponentBase::Tick(const int count) { if (count % prescaler_ > 0) return; if (power_port_->GetIsOn()) { MainRoutine(count); @@ -39,7 +39,7 @@ void ComponentBase::Tick(int count) { } } -void ComponentBase::FastTick(int count) { +void ComponentBase::FastTick(const int count) { if (count % fast_prescaler_ > 0) return; if (power_port_->GetIsOn()) { FastUpdate(); diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 6f8428e7f..7dd6181f5 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -24,10 +24,10 @@ class ComponentBase : public ITickable { * @brief Constructor without power port * @note Power port is used as power on state * @param [in] prescaler: Frequency scale factor for normal update - * @param [in] clocl_gen: Clock generator + * @param [in] clock_gen: Clock generator * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(int prescaler, ClockGenerator* clock_gen, int fast_prescaler = 1); + ComponentBase(const int prescaler, ClockGenerator* clock_gen, const int fast_prescaler = 1); /** * @fn ComponentBase * @brief Constructor with power port @@ -36,7 +36,7 @@ class ComponentBase : public ITickable { * @param [in] power_port: Power port * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, int fast_prescaler = 1); + ComponentBase(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int fast_prescaler = 1); /** * @fn ComponentBase * @brief Copy constructor @@ -53,12 +53,12 @@ class ComponentBase : public ITickable { * @fn Tick * @brief The methods to input clock. This will be called periodically. */ - virtual void Tick(int count); + virtual void Tick(const int count); /** * @fn FastTick * @brief The methods to input fast clock. This will be called periodically. */ - virtual void FastTick(int fast_count); + virtual void FastTick(const int fast_count); protected: int prescaler_; //!< Frequency scale factor for normal update @@ -69,7 +69,7 @@ class ComponentBase : public ITickable { * @brief Pure virtual function periodically executed when the power switch is on. * @note The period is decided with the prescaler_ and the base clock. */ - virtual void MainRoutine(int time_count) = 0; + virtual void MainRoutine(const int time_count) = 0; /** * @fn FastUpdate From 8ebaf6432b94b728beb1a494cceda5ce4647db4c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:45:49 +0100 Subject: [PATCH 0723/1086] Fix function argument name --- src/components/base/component.cpp | 18 +++++++++--------- src/components/base/component.hpp | 12 ++++++------ 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index e5b83b7cf..426fe053e 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -5,27 +5,27 @@ #include "component.hpp" -ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_gen, const int fast_prescaler) : clock_generator_(clock_gen) { +ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_generator, const int fast_prescaler) : clock_generator_(clock_generator) { power_port_ = new PowerPort(); clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int fast_prescaler) - : clock_generator_(clock_gen), power_port_(power_port) { +ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int fast_prescaler) + : clock_generator_(clock_generator), power_port_(power_port) { clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(const ComponentBase& obj) { - prescaler_ = obj.prescaler_; - fast_prescaler_ = obj.fast_prescaler_; - needs_fast_update_ = obj.needs_fast_update_; - clock_generator_ = obj.clock_generator_; +ComponentBase::ComponentBase(const ComponentBase& object) { + prescaler_ = object.prescaler_; + fast_prescaler_ = object.fast_prescaler_; + needs_fast_update_ = object.needs_fast_update_; + clock_generator_ = object.clock_generator_; clock_generator_->RegisterComponent(this); - power_port_ = obj.power_port_; + power_port_ = object.power_port_; } ComponentBase::~ComponentBase() { clock_generator_->RemoveComponent(this); } diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 7dd6181f5..79bc3f4d3 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -24,24 +24,24 @@ class ComponentBase : public ITickable { * @brief Constructor without power port * @note Power port is used as power on state * @param [in] prescaler: Frequency scale factor for normal update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const int prescaler, ClockGenerator* clock_gen, const int fast_prescaler = 1); + ComponentBase(const int prescaler, ClockGenerator* clock_generator, const int fast_prescaler = 1); /** * @fn ComponentBase * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for normal update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int fast_prescaler = 1); + ComponentBase(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int fast_prescaler = 1); /** * @fn ComponentBase * @brief Copy constructor */ - ComponentBase(const ComponentBase& obj); + ComponentBase(const ComponentBase& object); /** * @fn ~ComponentBase * @brief Destructor @@ -58,7 +58,7 @@ class ComponentBase : public ITickable { * @fn FastTick * @brief The methods to input fast clock. This will be called periodically. */ - virtual void FastTick(const int fast_count); + virtual void FastTick(const int count); protected: int prescaler_; //!< Frequency scale factor for normal update From 870aeac80f5606abfebd8ba421aa828961de60e7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:52:51 +0100 Subject: [PATCH 0724/1086] Add const to function arguments --- src/components/base/component.cpp | 4 ++-- src/components/base/component.hpp | 2 +- src/components/base/interface_tickable.hpp | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index 426fe053e..d4d0346c9 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -39,8 +39,8 @@ void ComponentBase::Tick(const int count) { } } -void ComponentBase::FastTick(const int count) { - if (count % fast_prescaler_ > 0) return; +void ComponentBase::FastTick(const int fast_count) { + if (fast_count % fast_prescaler_ > 0) return; if (power_port_->GetIsOn()) { FastUpdate(); } else { diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 79bc3f4d3..da3089b0c 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -58,7 +58,7 @@ class ComponentBase : public ITickable { * @fn FastTick * @brief The methods to input fast clock. This will be called periodically. */ - virtual void FastTick(const int count); + virtual void FastTick(const int fast_count); protected: int prescaler_; //!< Frequency scale factor for normal update diff --git a/src/components/base/interface_tickable.hpp b/src/components/base/interface_tickable.hpp index dd185fab6..8dafea292 100644 --- a/src/components/base/interface_tickable.hpp +++ b/src/components/base/interface_tickable.hpp @@ -16,13 +16,13 @@ class ITickable { * @fn Tick * @brief Pure virtual function to update clock of components */ - virtual void Tick(int count) = 0; + virtual void Tick(const int count) = 0; /** * @fn FastTick * @brief Pure virtual function to update clock faster than the base component update period of components * @note Usec ase: Calculate high-frequency disturbances */ - virtual void FastTick(int fast_count) = 0; + virtual void FastTick(const int fast_count) = 0; // Whether or not high-frequency disturbances need to be calculated /** @@ -34,7 +34,7 @@ class ITickable { * @fn SetNeedsFastUpdate * @brief Set fast update flag */ - inline void SetNeedsFastUpdate(bool need_fast_update) { needs_fast_update_ = need_fast_update; } + inline void SetNeedsFastUpdate(const bool need_fast_update) { needs_fast_update_ = need_fast_update; } protected: bool needs_fast_update_ = false; //!< Whether or not high-frequency disturbances need to be calculated From f7a31fa9b78a5777bfbc725bc83376cfc6c23fa3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:55:13 +0100 Subject: [PATCH 0725/1086] Change to unsigned --- src/components/base/component.cpp | 5 +++-- src/components/base/component.hpp | 8 ++++---- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index d4d0346c9..679456f55 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -5,14 +5,15 @@ #include "component.hpp" -ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_generator, const int fast_prescaler) : clock_generator_(clock_generator) { +ComponentBase::ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler) + : clock_generator_(clock_generator) { power_port_ = new PowerPort(); clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int fast_prescaler) +ComponentBase::ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler) : clock_generator_(clock_generator), power_port_(power_port) { clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index da3089b0c..2c88c1e6a 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -27,7 +27,7 @@ class ComponentBase : public ITickable { * @param [in] clock_generator: Clock generator * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const int prescaler, ClockGenerator* clock_generator, const int fast_prescaler = 1); + ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler = 1); /** * @fn ComponentBase * @brief Constructor with power port @@ -36,7 +36,7 @@ class ComponentBase : public ITickable { * @param [in] power_port: Power port * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int fast_prescaler = 1); + ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler = 1); /** * @fn ComponentBase * @brief Copy constructor @@ -61,8 +61,8 @@ class ComponentBase : public ITickable { virtual void FastTick(const int fast_count); protected: - int prescaler_; //!< Frequency scale factor for normal update - int fast_prescaler_ = 1; //!< Frequency scale factor for fast update + unsigned int prescaler_; //!< Frequency scale factor for normal update + unsigned int fast_prescaler_ = 1; //!< Frequency scale factor for fast update /** * @fn MainRoutine From f91e5cf9e2c6ba63e67550c9d739917978623720 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 22:58:57 +0100 Subject: [PATCH 0726/1086] Change to unsigned --- src/components/base/component.cpp | 4 ++-- src/components/base/component.hpp | 4 ++-- src/components/base/interface_tickable.hpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index 679456f55..42239d38d 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -31,7 +31,7 @@ ComponentBase::ComponentBase(const ComponentBase& object) { ComponentBase::~ComponentBase() { clock_generator_->RemoveComponent(this); } -void ComponentBase::Tick(const int count) { +void ComponentBase::Tick(const unsigned int count) { if (count % prescaler_ > 0) return; if (power_port_->GetIsOn()) { MainRoutine(count); @@ -40,7 +40,7 @@ void ComponentBase::Tick(const int count) { } } -void ComponentBase::FastTick(const int fast_count) { +void ComponentBase::FastTick(const unsigned int fast_count) { if (fast_count % fast_prescaler_ > 0) return; if (power_port_->GetIsOn()) { FastUpdate(); diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 2c88c1e6a..4c0a905d0 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -53,12 +53,12 @@ class ComponentBase : public ITickable { * @fn Tick * @brief The methods to input clock. This will be called periodically. */ - virtual void Tick(const int count); + virtual void Tick(const unsigned int count); /** * @fn FastTick * @brief The methods to input fast clock. This will be called periodically. */ - virtual void FastTick(const int fast_count); + virtual void FastTick(const unsigned int fast_count); protected: unsigned int prescaler_; //!< Frequency scale factor for normal update diff --git a/src/components/base/interface_tickable.hpp b/src/components/base/interface_tickable.hpp index 8dafea292..3d7171aeb 100644 --- a/src/components/base/interface_tickable.hpp +++ b/src/components/base/interface_tickable.hpp @@ -16,13 +16,13 @@ class ITickable { * @fn Tick * @brief Pure virtual function to update clock of components */ - virtual void Tick(const int count) = 0; + virtual void Tick(const unsigned int count) = 0; /** * @fn FastTick * @brief Pure virtual function to update clock faster than the base component update period of components * @note Usec ase: Calculate high-frequency disturbances */ - virtual void FastTick(const int fast_count) = 0; + virtual void FastTick(const unsigned int fast_count) = 0; // Whether or not high-frequency disturbances need to be calculated /** From 31b4794631b5a1f3592fffec6190c6c954dd6c4e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 23:16:57 +0100 Subject: [PATCH 0727/1086] Change to unsigned --- src/environment/global/clock_generator.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 612bb9220..0589683ab 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -54,7 +54,7 @@ class ClockGenerator { private: std::vector components_; //!< Component list fot tick - int timer_count_; //!< Timer count TODO: consider size, unsigned + unsigned int timer_count_; //!< Timer count }; #endif // S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ From fe02de1036676374ebe8de7935e6fb947efe0800 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 23:25:38 +0100 Subject: [PATCH 0728/1086] Fix comments --- src/environment/global/clock_generator.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 0589683ab..095350bcf 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -26,13 +26,13 @@ class ClockGenerator { /** * @fn RegisterComponent * @brief Register component which has ITickable - * @param [in] ticlable: Component class + * @param [in] tickable: Component class */ void RegisterComponent(ITickable* tickable); /** * @fn RemoveComponent * @brief Removed registered component - * @param [in] ticlable: Registered component class + * @param [in] tickable: Registered component class */ void RemoveComponent(ITickable* tickable); /** @@ -54,7 +54,7 @@ class ClockGenerator { private: std::vector components_; //!< Component list fot tick - unsigned int timer_count_; //!< Timer count + unsigned int timer_count_; //!< Timer count TODO: change to long? }; #endif // S2E_ENVIRONMENT_GLOBAL_CLOCK_GENERATOR_HPP_ From 237b87af85c20c59b9592e10e7ee3c131cc79ca0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 23:29:59 +0100 Subject: [PATCH 0729/1086] Rename ComponentBase to Component --- src/components/base/component.cpp | 12 +++++----- src/components/base/component.hpp | 22 +++++++++---------- .../examples/example_change_structure.cpp | 3 +-- .../examples/example_change_structure.hpp | 4 ++-- .../example_i2c_controller_for_hils.cpp | 2 +- .../example_i2c_controller_for_hils.hpp | 4 ++-- .../examples/example_i2c_target_for_hils.cpp | 2 +- .../examples/example_i2c_target_for_hils.hpp | 4 ++-- .../example_serial_communication_for_hils.cpp | 2 +- .../example_serial_communication_for_hils.hpp | 4 ++-- .../example_serial_communication_with_obc.cpp | 4 ++-- .../example_serial_communication_with_obc.hpp | 4 ++-- src/components/ideal/force_generator.cpp | 2 +- src/components/ideal/force_generator.hpp | 4 ++-- src/components/ideal/torque_generator.cpp | 2 +- src/components/ideal/torque_generator.hpp | 4 ++-- src/components/real/aocs/gnss_receiver.cpp | 4 ++-- src/components/real/aocs/gnss_receiver.hpp | 4 ++-- src/components/real/aocs/gyro_sensor.cpp | 4 ++-- src/components/real/aocs/gyro_sensor.hpp | 4 ++-- src/components/real/aocs/magnetometer.cpp | 4 ++-- src/components/real/aocs/magnetometer.hpp | 4 ++-- src/components/real/aocs/magnetorquer.cpp | 4 ++-- src/components/real/aocs/magnetorquer.hpp | 4 ++-- src/components/real/aocs/reaction_wheel.cpp | 4 ++-- src/components/real/aocs/reaction_wheel.hpp | 4 ++-- src/components/real/aocs/star_sensor.cpp | 4 ++-- src/components/real/aocs/star_sensor.hpp | 4 ++-- src/components/real/aocs/sun_sensor.cpp | 4 ++-- src/components/real/aocs/sun_sensor.hpp | 4 ++-- src/components/real/cdh/on_board_computer.cpp | 6 ++--- src/components/real/cdh/on_board_computer.hpp | 4 ++-- .../real/cdh/on_board_computer_with_c2a.hpp | 2 +- src/components/real/mission/telescope.cpp | 2 +- src/components/real/mission/telescope.hpp | 4 ++-- src/components/real/power/battery.cpp | 6 ++--- src/components/real/power/battery.hpp | 4 ++-- .../real/power/pcu_initial_study.cpp | 4 ++-- .../real/power/pcu_initial_study.hpp | 4 ++-- .../real/power/power_control_unit.cpp | 4 ++-- .../real/power/power_control_unit.hpp | 4 ++-- .../real/power/solar_array_panel.cpp | 8 +++---- .../real/power/solar_array_panel.hpp | 4 ++-- .../real/propulsion/simple_thruster.cpp | 4 ++-- .../real/propulsion/simple_thruster.hpp | 4 ++-- 45 files changed, 99 insertions(+), 100 deletions(-) diff --git a/src/components/base/component.cpp b/src/components/base/component.cpp index 42239d38d..82fdf14c9 100644 --- a/src/components/base/component.cpp +++ b/src/components/base/component.cpp @@ -5,7 +5,7 @@ #include "component.hpp" -ComponentBase::ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler) +Component::Component(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler) : clock_generator_(clock_generator) { power_port_ = new PowerPort(); clock_generator_->RegisterComponent(this); @@ -13,14 +13,14 @@ ComponentBase::ComponentBase(const unsigned int prescaler, ClockGenerator* clock fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler) +Component::Component(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler) : clock_generator_(clock_generator), power_port_(power_port) { clock_generator_->RegisterComponent(this); prescaler_ = (prescaler > 0) ? prescaler : 1; fast_prescaler_ = (fast_prescaler > 0) ? fast_prescaler : 1; } -ComponentBase::ComponentBase(const ComponentBase& object) { +Component::Component(const Component& object) { prescaler_ = object.prescaler_; fast_prescaler_ = object.fast_prescaler_; needs_fast_update_ = object.needs_fast_update_; @@ -29,9 +29,9 @@ ComponentBase::ComponentBase(const ComponentBase& object) { power_port_ = object.power_port_; } -ComponentBase::~ComponentBase() { clock_generator_->RemoveComponent(this); } +Component::~Component() { clock_generator_->RemoveComponent(this); } -void ComponentBase::Tick(const unsigned int count) { +void Component::Tick(const unsigned int count) { if (count % prescaler_ > 0) return; if (power_port_->GetIsOn()) { MainRoutine(count); @@ -40,7 +40,7 @@ void ComponentBase::Tick(const unsigned int count) { } } -void ComponentBase::FastTick(const unsigned int fast_count) { +void Component::FastTick(const unsigned int fast_count) { if (fast_count % fast_prescaler_ > 0) return; if (power_port_->GetIsOn()) { FastUpdate(); diff --git a/src/components/base/component.hpp b/src/components/base/component.hpp index 4c0a905d0..cb4049985 100644 --- a/src/components/base/component.hpp +++ b/src/components/base/component.hpp @@ -13,40 +13,40 @@ #include "interface_tickable.hpp" /** - * @class ComponentBase + * @class Component * @brief Base class for component emulation. All components have to inherit this. - * @details ComponentBase ha clock and power on/off features + * @details Component ha clock and power on/off features */ -class ComponentBase : public ITickable { +class Component : public ITickable { public: /** - * @fn ComponentBase + * @fn Component * @brief Constructor without power port * @note Power port is used as power on state * @param [in] prescaler: Frequency scale factor for normal update * @param [in] clock_generator: Clock generator * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler = 1); + Component(const unsigned int prescaler, ClockGenerator* clock_generator, const unsigned int fast_prescaler = 1); /** - * @fn ComponentBase + * @fn Component * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for normal update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] fast_prescaler: Frequency scale factor for fast update (used only for component faster than component update period) */ - ComponentBase(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler = 1); + Component(const unsigned int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const unsigned int fast_prescaler = 1); /** - * @fn ComponentBase + * @fn Component * @brief Copy constructor */ - ComponentBase(const ComponentBase& object); + Component(const Component& object); /** - * @fn ~ComponentBase + * @fn ~Component * @brief Destructor */ - virtual ~ComponentBase(); + virtual ~Component(); // Override functions for ITickable /** diff --git a/src/components/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp index 15d2f5775..5bfc7a476 100644 --- a/src/components/examples/example_change_structure.cpp +++ b/src/components/examples/example_change_structure.cpp @@ -5,8 +5,7 @@ #include "example_change_structure.hpp" -ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure) - : ComponentBase(1, clock_gen), structure_(structure) {} +ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure) : Component(1, clock_gen), structure_(structure) {} ExampleChangeStructure::~ExampleChangeStructure() {} diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 11c303f40..a5d27626c 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -15,7 +15,7 @@ * @class ExampleChangeStructure * @brief Class to show an example to change satellite structure information */ -class ExampleChangeStructure : public ComponentBase, public ILoggable { +class ExampleChangeStructure : public Component, public ILoggable { public: /** * @fn ExampleChangeStructure @@ -30,7 +30,7 @@ class ExampleChangeStructure : public ComponentBase, public ILoggable { */ ~ExampleChangeStructure(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp index c22f20180..b9c7e84e1 100644 --- a/src/components/examples/example_i2c_controller_for_hils.cpp +++ b/src/components/examples/example_i2c_controller_for_hils.cpp @@ -7,7 +7,7 @@ ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager) - : ComponentBase(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buf_size, rx_buf_size, hils_port_manager) {} + : Component(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buf_size, rx_buf_size, hils_port_manager) {} ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 92ea8119d..ee4a96d37 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -18,7 +18,7 @@ * SC18IM700 Data Sheet: https://www.nxp.com/docs/en/data-sheet/SC18IM700.pdf * telemetry size = 5 bytes(ASCII) */ -class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCommunicationBase { +class ExampleI2cControllerForHils : public Component, public I2cControllerCommunicationBase { public: /** * @fn ExampleI2cControllerForHils @@ -40,7 +40,7 @@ class ExampleI2cControllerForHils : public ComponentBase, public I2cControllerCo ~ExampleI2cControllerForHils(); protected: - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to receive command and send telemetry diff --git a/src/components/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp index aa81abc33..4bb0d020e 100644 --- a/src/components/examples/example_i2c_target_for_hils.cpp +++ b/src/components/examples/example_i2c_target_for_hils.cpp @@ -7,7 +7,7 @@ ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) - : ComponentBase(prescaler, clock_gen), ObcI2cTargetCommunicationBase(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} + : Component(prescaler, clock_gen), ObcI2cTargetCommunicationBase(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} ExampleI2cTargetForHils::~ExampleI2cTargetForHils() {} diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 79b22eac1..c595f7303 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -19,7 +19,7 @@ * Telemetry size = 5 bytes(ASCII) * Telemetry changes; ABCDE, BCDEF, ..., VWXYZ, ABCDE, ... */ -class ExampleI2cTargetForHils : public ComponentBase, public ObcI2cTargetCommunicationBase { +class ExampleI2cTargetForHils : public Component, public ObcI2cTargetCommunicationBase { public: /** * @fn ExampleI2cTargetForHils @@ -41,7 +41,7 @@ class ExampleI2cTargetForHils : public ComponentBase, public ObcI2cTargetCommuni ~ExampleI2cTargetForHils(); protected: - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to receive command and send telemetry diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index 77e8584f5..31fbf9810 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -9,7 +9,7 @@ ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id) - : ComponentBase(300, clock_gen), ObcCommunicationBase(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} + : Component(300, clock_gen), ObcCommunicationBase(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} ExampleSerialCommunicationForHils::~ExampleSerialCommunicationForHils() {} diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 864d81e21..d23276817 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -20,7 +20,7 @@ * - the last byte : \0 * The responder mode: ExpHils returns the message as received */ -class ExampleSerialCommunicationForHils : public ComponentBase, public ObcCommunicationBase { +class ExampleSerialCommunicationForHils : public Component, public ObcCommunicationBase { public: /** * @fn ExampleSerialCommunicationForHils @@ -43,7 +43,7 @@ class ExampleSerialCommunicationForHils : public ComponentBase, public ObcCommun ~ExampleSerialCommunicationForHils(); protected: - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to receive command and send telemetry diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index c7adbd473..b4e8287be 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -8,11 +8,11 @@ #include ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) - : ComponentBase(1000, clock_gen), ObcCommunicationBase(port_id, obc) { + : Component(1000, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) - : ComponentBase(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { + : Component(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { Initialize(); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 4e178166c..551deb749 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -25,7 +25,7 @@ * - The last byte: "\n" * - The telemetry is automatically generated */ -class ExampleSerialCommunicationWithObc : public ComponentBase, public ObcCommunicationBase, public IGPIOCompo { +class ExampleSerialCommunicationWithObc : public Component, public ObcCommunicationBase, public IGPIOCompo { public: /** * @fn ExampleSerialCommunicationWithObc @@ -52,7 +52,7 @@ class ExampleSerialCommunicationWithObc : public ComponentBase, public ObcCommun ~ExampleSerialCommunicationWithObc(); protected: - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to receive command and send telemetry diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 5e622ac14..5c5da2d43 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -10,7 +10,7 @@ // Constructor ForceGenerator::ForceGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_N, const double direction_error_standard_deviation_rad, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), magnitude_noise_(0.0, magnitude_error_standard_deviation_N), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { diff --git a/src/components/ideal/force_generator.hpp b/src/components/ideal/force_generator.hpp index 029461134..0c1e3b9a1 100644 --- a/src/components/ideal/force_generator.hpp +++ b/src/components/ideal/force_generator.hpp @@ -16,7 +16,7 @@ * @class ForceGenerator * @brief Ideal component which can generate for control algorithm test */ -class ForceGenerator : public ComponentBase, public ILoggable { +class ForceGenerator : public Component, public ILoggable { public: /** * @fn ForceGenerator @@ -35,7 +35,7 @@ class ForceGenerator : public ComponentBase, public ILoggable { */ ~ForceGenerator(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 6fde1d1c1..94cb026f7 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -10,7 +10,7 @@ // Constructor TorqueGenerator::TorqueGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_Nm, const double direction_error_standard_deviation_rad, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), magnitude_noise_(0.0, magnitude_error_standard_deviation_Nm), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index 7330c1d18..4ceee221e 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -16,7 +16,7 @@ * @class TorqueGenerator * @brief Ideal component which can generate for control algorithm test */ -class TorqueGenerator : public ComponentBase, public ILoggable { +class TorqueGenerator : public Component, public ILoggable { public: /** * @fn TorqueGenerator @@ -35,7 +35,7 @@ class TorqueGenerator : public ComponentBase, public ILoggable { */ ~TorqueGenerator(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate torque generation diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 4278d75a7..0da9a5282 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -12,7 +12,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), ch_max_(ch_max), antenna_position_b_(ant_pos_b), @@ -30,7 +30,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, Power const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) - : ComponentBase(prescaler, clock_gen, power_port), + : Component(prescaler, clock_gen, power_port), id_(id), ch_max_(ch_max), antenna_position_b_(ant_pos_b), diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 1fd57f687..2cf873cad 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -41,7 +41,7 @@ typedef struct _gnssinfo { * @class GNSSReceiver * @brief Class to emulate GNSS receiver */ -class GNSSReceiver : public ComponentBase, public ILoggable { +class GNSSReceiver : public Component, public ILoggable { public: /** * @fn GNSSReceiver @@ -83,7 +83,7 @@ class GNSSReceiver : public ComponentBase, public ILoggable { const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index 6eb3d1b4d..c5b10f6d5 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -7,11 +7,11 @@ Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} Gyro::~Gyro() {} diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index e525e602d..beab20915 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -19,7 +19,7 @@ const size_t kGyroDim = 3; //!< Dimension of gyro sensor * @class Gyro * @brief Class to emulate gyro sensor */ -class Gyro : public ComponentBase, public SensorBase, public ILoggable { +class Gyro : public Component, public SensorBase, public ILoggable { public: /** * @fn Gyro @@ -52,7 +52,7 @@ class Gyro : public ComponentBase, public SensorBase, public ILoggable */ ~Gyro(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index a9c19c5e1..e520b45e3 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -8,10 +8,10 @@ MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : ComponentBase(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + : Component(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : ComponentBase(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + : Component(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index eef494fd9..83712dde0 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -19,7 +19,7 @@ const size_t kMagDim = 3; //!< Dimension of magnetometer * @class MagSensor * @brief Class to emulate magnetometer */ -class MagSensor : public ComponentBase, public SensorBase, public ILoggable { +class MagSensor : public Component, public SensorBase, public ILoggable { public: /** * @fn MagSensor @@ -52,7 +52,7 @@ class MagSensor : public ComponentBase, public SensorBase, public ILogg */ ~MagSensor(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 433736f0a..0b9190223 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -14,7 +14,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), q_c2b_(q_b2c_.Conjugate()), @@ -33,7 +33,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) - : ComponentBase(prescaler, clock_gen, power_port), + : Component(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), q_c2b_(q_b2c_.Conjugate()), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index ef66997a4..fd51efa80 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -22,7 +22,7 @@ const size_t kMtqDim = 3; //!< Dimension of magnetorquer * @class MagTorquer * @brief Class to emulate magnetorquer */ -class MagTorquer : public ComponentBase, public ILoggable { +class MagTorquer : public Component, public ILoggable { public: /** * @fn MagTorquer @@ -68,7 +68,7 @@ class MagTorquer : public ComponentBase, public ILoggable { const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to output torque diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 89e6f2c27..d83d7ac3b 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -23,7 +23,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, c bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) - : ComponentBase(prescaler, clock_gen, fast_prescaler), + : Component(prescaler, clock_gen, fast_prescaler), id_(id), inertia_(inertia), max_torque_(max_torque), @@ -51,7 +51,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, P vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) - : ComponentBase(prescaler, clock_gen, power_port, fast_prescaler), + : Component(prescaler, clock_gen, power_port, fast_prescaler), id_(id), inertia_(inertia), max_torque_(max_torque), diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 5aa1000af..32df88016 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -22,7 +22,7 @@ * @brief Class to emulate Reaction Wheel * @note For one reaction wheel */ -class RWModel : public ComponentBase, public ILoggable { +class RWModel : public Component, public ILoggable { public: /** * @fn RWModel @@ -99,7 +99,7 @@ class RWModel : public ComponentBase, public ILoggable { double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to output torque of normal RW diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index a45bd6e46..3b941be23 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -19,7 +19,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_gen, const int id, const lib const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), rot_(global_randomization.MakeSeed()), @@ -42,7 +42,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) - : ComponentBase(prescaler, clock_gen, power_port), + : Component(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), rot_(global_randomization.MakeSeed()), diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 73e280601..13ccafa89 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -22,7 +22,7 @@ * @class STT * @brief Class to emulate star tracker */ -class STT : public ComponentBase, public ILoggable { +class STT : public Component, public ILoggable { public: /** * @fn STT @@ -72,7 +72,7 @@ class STT : public ComponentBase, public ILoggable { const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 1f35c66a9..99f56e39d 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -16,7 +16,7 @@ using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), q_b2c_(q_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), @@ -30,7 +30,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : ComponentBase(prescaler, clock_gen, power_port), + : Component(prescaler, clock_gen, power_port), id_(id), q_b2c_(q_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 04a0a941f..4919d7c79 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -19,7 +19,7 @@ * @class SunSensor * @brief Class to emulate sun sensor */ -class SunSensor : public ComponentBase, public ILoggable { +class SunSensor : public Component, public ILoggable { public: /** * @fn SunSensor @@ -58,7 +58,7 @@ class SunSensor : public ComponentBase, public ILoggable { const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine for sensor observation diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index bda53a113..a54289e91 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -4,12 +4,12 @@ */ #include "on_board_computer.hpp" -OBC::OBC(ClockGenerator* clock_gen) : ComponentBase(1, clock_gen) { Initialize(); } +OBC::OBC(ClockGenerator* clock_gen) : Component(1, clock_gen) { Initialize(); } -OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port) : ComponentBase(prescaler, clock_gen, power_port) { Initialize(); } +OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port) : Component(prescaler, clock_gen, power_port) { Initialize(); } OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption) - : ComponentBase(prescaler, clock_gen, power_port) { + : Component(prescaler, clock_gen, power_port) { power_port_->SetMinimumVoltage(minimum_voltage); power_port_->SetAssumedPowerConsumption(assumed_power_consumption); Initialize(); diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 4264a91c6..8da989776 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -18,7 +18,7 @@ * @brief Class to emulate on board computer * @note OBC is connected with other components to communicate, and flight software is executed in OBC. */ -class OBC : public ComponentBase { +class OBC : public Component { public: /** * @fn OBC @@ -192,7 +192,7 @@ class OBC : public ComponentBase { */ virtual void Initialize(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to execute flight software diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index a642ee710..7ede0d2c9 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -253,7 +253,7 @@ class OBC_C2A : public OBC { bool is_initialized = false; //!< Is initialized flag const int timing_regulator_; //!< Timing regulator to update flight software faster than the component update - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to execute C2A diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 6535c53e0..9aacc091c 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -15,7 +15,7 @@ Telescope::Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info) - : ComponentBase(1, clock_gen), + : Component(1, clock_gen), q_b2c_(q_b2c), sun_forbidden_angle_(sun_forbidden_angle), earth_forbidden_angle_(earth_forbidden_angle), diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 794ce6f33..9a086e181 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -28,7 +28,7 @@ struct Star { * @class Telescope * @brief Component emulation: Telescope */ -class Telescope : public ComponentBase, public ILoggable { +class Telescope : public Component, public ILoggable { public: Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, @@ -77,7 +77,7 @@ class Telescope : public ComponentBase, public ILoggable { */ bool JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 5f345cadb..686e6c6f6 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -10,7 +10,7 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance, double compo_step_time) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_capacity_(cell_capacity), @@ -24,7 +24,7 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_gen, int number_of_series, i BAT::BAT(ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance) - : ComponentBase(10, clock_gen), + : Component(10, clock_gen), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_capacity_(cell_capacity), @@ -36,7 +36,7 @@ BAT::BAT(ClockGenerator* clock_gen, int number_of_series, int number_of_parallel compo_step_time_(0.1) {} BAT::BAT(const BAT& obj) - : ComponentBase(obj), + : Component(obj), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), cell_capacity_(obj.cell_capacity_), diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 28f912fba..044f051a2 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -15,7 +15,7 @@ * @class BAT * @brief Component emulation of battery */ -class BAT : public ComponentBase, public ILoggable { +class BAT : public Component, public ILoggable { public: /** * @fn BAT @@ -118,7 +118,7 @@ class BAT : public ComponentBase, public ILoggable { double bat_resistance_; //!< Battery internal resistance [Ohm] double compo_step_time_; //!< Component step time [sec] - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 9558b27c4..0f0109b4a 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -10,7 +10,7 @@ #include PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), saps_(saps), bat_(bat), cc_charge_current_(bat->GetCCChargeCurrent()), @@ -21,7 +21,7 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge } PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_gen, const std::vector saps, BAT* bat) - : ComponentBase(10, clock_gen), + : Component(10, clock_gen), saps_(saps), bat_(bat), cc_charge_current_(bat->GetCCChargeCurrent()), diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index d88461a96..b5ab9ed54 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -13,7 +13,7 @@ #include "battery.hpp" #include "solar_array_panel.hpp" -class PCU_InitialStudy : public ComponentBase, public ILoggable { +class PCU_InitialStudy : public Component, public ILoggable { public: /** * @fn PCU_InitialStudy @@ -60,7 +60,7 @@ class PCU_InitialStudy : public ComponentBase, public ILoggable { double power_consumption_; //!< Power consumption [W] double compo_step_time_; //!< Component step time [sec] - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index 320a8feb6..087624a2b 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -4,9 +4,9 @@ */ #include "power_control_unit.hpp" -PCU::PCU(ClockGenerator* clock_gen) : ComponentBase(1, clock_gen) {} +PCU::PCU(ClockGenerator* clock_gen) : Component(1, clock_gen) {} -PCU::PCU(int prescaler, ClockGenerator* clock_gen) : ComponentBase(prescaler, clock_gen) {} +PCU::PCU(int prescaler, ClockGenerator* clock_gen) : Component(prescaler, clock_gen) {} PCU::~PCU() {} diff --git a/src/components/real/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp index 9ae65ec96..75029a2f3 100644 --- a/src/components/real/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -16,7 +16,7 @@ * @class PCU * @brief Component emulation of Power Control Unit */ -class PCU : public ComponentBase, public ILoggable { +class PCU : public Component, public ILoggable { public: /** * @fn PCU @@ -37,7 +37,7 @@ class PCU : public ComponentBase, public ILoggable { */ ~PCU(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index df21f1c3b..cfcd697e6 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -11,7 +11,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -29,7 +29,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -46,7 +46,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s SAP::SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : ComponentBase(10, clock_gen), + : Component(10, clock_gen), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -62,7 +62,7 @@ SAP::SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_ } SAP::SAP(const SAP& obj) - : ComponentBase(obj), + : Component(obj), id_(obj.id_), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 4592b05e5..39dc57ab8 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -13,7 +13,7 @@ #include "../../base/component.hpp" -class SAP : public ComponentBase, public ILoggable { +class SAP : public Component, public ILoggable { public: /** * @fn SAP @@ -123,7 +123,7 @@ class SAP : public ComponentBase, public ILoggable { static const double light_speed_; //!< Speed of light TODO: Use PhysicalConstant? double compo_step_time_; //!< Component step time [sec] - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 44bb8af0e..37dbd2983 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -12,7 +12,7 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen), + : Component(prescaler, clock_gen), id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), @@ -26,7 +26,7 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, c SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) - : ComponentBase(prescaler, clock_gen, power_port), + : Component(prescaler, clock_gen, power_port), id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index af95e7ee7..55a04b24e 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -19,7 +19,7 @@ * @class SimpleThruster * @brief Component emulation of simple thruster */ -class SimpleThruster : public ComponentBase, public ILoggable { +class SimpleThruster : public Component, public ILoggable { public: /** * @fn SimpleThruster @@ -61,7 +61,7 @@ class SimpleThruster : public ComponentBase, public ILoggable { */ ~SimpleThruster(); - // Override functions for ComponentBase + // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation From b0f7174939ceed47c3f7e8098e96b93dce84679d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 23:48:16 +0100 Subject: [PATCH 0730/1086] Rename function arguments --- src/components/base/gpio_connection_with_obc.cpp | 4 ++-- src/components/base/gpio_connection_with_obc.hpp | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/gpio_connection_with_obc.cpp b/src/components/base/gpio_connection_with_obc.cpp index 6f74b68fe..2906ca83f 100644 --- a/src/components/base/gpio_connection_with_obc.cpp +++ b/src/components/base/gpio_connection_with_obc.cpp @@ -14,6 +14,6 @@ ObcGpioBase::ObcGpioBase(const std::vector port_id, OBC* obc) : port_id_(po ObcGpioBase::~ObcGpioBase() {} -bool ObcGpioBase::Read(const int idx) { return obc_->GpioComponentRead(port_id_[idx]); } +bool ObcGpioBase::Read(const int index) { return obc_->GpioComponentRead(port_id_[index]); } -void ObcGpioBase::Write(const int idx, const bool is_high) { obc_->GpioComponentWrite(port_id_[idx], is_high); } +void ObcGpioBase::Write(const int index, const bool is_high) { obc_->GpioComponentWrite(port_id_[index], is_high); } diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index ab914d18d..da2b148f3 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -33,17 +33,17 @@ class ObcGpioBase { /** * @fn Read * @brief Read the GPIO state - * @param [in] idx: element index for port_id_ vector, not the GPIO port ID for OBC. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC. * @return High(True) or Low(False) of GPIO state */ - bool Read(const int idx); + bool Read(const int index); /** * @fn Write * @brief Write the GPIO state - * @param [in] idx: element index for port_id_ vector, not the GPIO port ID for OBC. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC. * @param [in] is_high: High(True) or Low(False) of GPIO state */ - void Write(const int idx, const bool is_high); + void Write(const int index, const bool is_high); private: std::vector port_id_; //!< Port ID GPIO line From cd879d03b1cf649cd82ee4bb195b574bd665cda7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 25 Feb 2023 23:50:04 +0100 Subject: [PATCH 0731/1086] Rename ObcGpioBase to GpioConnectionWithObc --- src/components/base/gpio_connection_with_obc.cpp | 8 ++++---- src/components/base/gpio_connection_with_obc.hpp | 12 ++++++------ 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/base/gpio_connection_with_obc.cpp b/src/components/base/gpio_connection_with_obc.cpp index 2906ca83f..7e9f8a6b5 100644 --- a/src/components/base/gpio_connection_with_obc.cpp +++ b/src/components/base/gpio_connection_with_obc.cpp @@ -6,14 +6,14 @@ #include "gpio_connection_with_obc.hpp" -ObcGpioBase::ObcGpioBase(const std::vector port_id, OBC* obc) : port_id_(port_id), obc_(obc) { +GpioConnectionWithObc::GpioConnectionWithObc(const std::vector port_id, OBC* obc) : port_id_(port_id), obc_(obc) { for (size_t i = 0; i < port_id_.size(); i++) { obc_->GpioConnectPort(port_id_[i]); } } -ObcGpioBase::~ObcGpioBase() {} +GpioConnectionWithObc::~GpioConnectionWithObc() {} -bool ObcGpioBase::Read(const int index) { return obc_->GpioComponentRead(port_id_[index]); } +bool GpioConnectionWithObc::Read(const int index) { return obc_->GpioComponentRead(port_id_[index]); } -void ObcGpioBase::Write(const int index, const bool is_high) { obc_->GpioComponentWrite(port_id_[index], is_high); } +void GpioConnectionWithObc::Write(const int index, const bool is_high) { obc_->GpioComponentWrite(port_id_[index], is_high); } diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index da2b148f3..a520c7bf4 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -10,24 +10,24 @@ #include "../real/cdh/on_board_computer.hpp" /** - * @class ObcGpioBase + * @class GpioConnectionWithObc * @brief Base class for GPIO communication with OBC flight software * @note Components which want to communicate with OBC using GPIO have to inherit this. */ -class ObcGpioBase { +class GpioConnectionWithObc { public: /** - * @fn ObcGpioBase + * @fn GpioConnectionWithObc * @brief Constructor for SILS mode * @param [in] port_id: Port ID GPIO line * @param [in] obc: The communication target OBC */ - ObcGpioBase(const std::vector port_id, OBC* obc); + GpioConnectionWithObc(const std::vector port_id, OBC* obc); /** - * @fn ~ObcGpioBase + * @fn ~GpioConnectionWithObc * @brief Destructor */ - ~ObcGpioBase(); + ~GpioConnectionWithObc(); protected: /** From 9cc496b5e5727594b8a003668331d438dbb455bb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:09:46 +0100 Subject: [PATCH 0732/1086] Rename private variables and arguments --- src/components/base/i2c_controller.cpp | 26 +++---- src/components/base/i2c_controller.hpp | 26 +++---- .../i2c_target_communication_with_obc.cpp | 52 ++++++------- .../i2c_target_communication_with_obc.hpp | 18 ++--- .../base/uart_communication_with_obc.cpp | 76 +++++++++---------- .../base/uart_communication_with_obc.hpp | 18 ++--- .../example_i2c_controller_for_hils.cpp | 4 +- .../example_i2c_controller_for_hils.hpp | 6 +- src/components/ports/uart_port.cpp | 10 +-- src/components/ports/uart_port.hpp | 6 +- src/components/real/cdh/on_board_computer.cpp | 4 +- src/components/real/cdh/on_board_computer.hpp | 6 +- .../real/cdh/on_board_computer_with_c2a.cpp | 4 +- .../real/cdh/on_board_computer_with_c2a.hpp | 6 +- src/simulation/hils/hils_port_manager.cpp | 14 ++-- src/simulation/hils/hils_port_manager.hpp | 12 +-- 16 files changed, 144 insertions(+), 144 deletions(-) diff --git a/src/components/base/i2c_controller.cpp b/src/components/base/i2c_controller.cpp index 2069417e8..6ef2b7fbc 100644 --- a/src/components/base/i2c_controller.cpp +++ b/src/components/base/i2c_controller.cpp @@ -7,27 +7,27 @@ #include I2cControllerCommunicationBase::I2cControllerCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, - const unsigned int tx_buf_size, const unsigned int rx_buf_size, + const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), - tx_buf_size_(tx_buf_size), - rx_buf_size_(rx_buf_size), + tx_buffer_size_(tx_buffer_size), + rx_buffer_size_(rx_buffer_size), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; - int ret = hils_port_manager_->I2cControllerConnectComPort(hils_port_id_, baud_rate_, tx_buf_size_, rx_buf_size_); + simulation_mode_ = OBC_COM_UART_MODE::HILS; + int ret = hils_port_manager_->I2cControllerConnectComPort(hils_port_id_, baud_rate_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Error: I2cCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:OFF Check compo initialization"); #endif } I2cControllerCommunicationBase::~I2cControllerCommunicationBase() { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return; + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return; int ret = hils_port_manager_->I2cControllerCloseComPort(hils_port_id_); if (ret != 0) { @@ -35,12 +35,12 @@ I2cControllerCommunicationBase::~I2cControllerCommunicationBase() { } } -int I2cControllerCommunicationBase::ReceiveTelemetry(const unsigned char len) { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; - return hils_port_manager_->I2cControllerReceive(hils_port_id_, &rx_buffer_.front(), 0, len); +int I2cControllerCommunicationBase::ReceiveTelemetry(const unsigned char length) { + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + return hils_port_manager_->I2cControllerReceive(hils_port_id_, &rx_buffer_.front(), 0, length); } -int I2cControllerCommunicationBase::SendCommand(const unsigned char len) { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; - return hils_port_manager_->I2cControllerSend(hils_port_id_, &tx_buffer_.front(), 0, len); +int I2cControllerCommunicationBase::SendCommand(const unsigned char length) { + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + return hils_port_manager_->I2cControllerSend(hils_port_id_, &tx_buffer_.front(), 0, length); } diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 1b1d21c0b..973954407 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -23,12 +23,12 @@ class I2cControllerCommunicationBase { * @brief Constructor * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port - * @param [in] tx_buf_size: TX (Controller to Target) buffer size - * @param [in] rx_buf_size: RX (Target to Controller) buffer size + * @param [in] tx_buffer_size: TX (Controller to Target) buffer size + * @param [in] rx_buffer_size: RX (Target to Controller) buffer size * @param [in] hils_port_manager: HILS port manager */ - I2cControllerCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buf_size, - const unsigned int rx_buf_size, HilsPortManager* hils_port_manager); + I2cControllerCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); /** * @fn ~I2cControllerCommunicationBase * @brief Destructor @@ -40,26 +40,26 @@ class I2cControllerCommunicationBase { * @fn ReceiveTelemetry * @brief Receive telemetry * @note This function works only HILS mode - * @param [in] len: Length of data + * @param [in] length: Length of data */ - int ReceiveTelemetry(const unsigned char len); + int ReceiveTelemetry(const unsigned char length); /** * @fn SendCommand * @brief Send command * @note This function works only HILS mode - * @param [in] len: Length of data + * @param [in] length: Length of data */ - int SendCommand(const unsigned char len); + int SendCommand(const unsigned char length); std::vector tx_buffer_; //!< TX (Controller to Target) buffer std::vector rx_buffer_; //!< RX (Target to Controller) buffer private: - unsigned int hils_port_id_; //!< ID of HILS communication port - int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 - unsigned int tx_buf_size_; //!< TX (Controller to Target) buffer size - unsigned int rx_buf_size_; //!< RX (Target to Controller) buffer size - OBC_COM_UART_MODE sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode (SILS or HILS) + unsigned int hils_port_id_; //!< ID of HILS communication port + int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 + unsigned int tx_buffer_size_; //!< TX (Controller to Target) buffer size + unsigned int rx_buffer_size_; //!< RX (Target to Controller) buffer size + OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode (SILS or HILS) HilsPortManager* hils_port_manager_; //!< HILS port manager }; diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index 8db952d68..37ed18fa6 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -9,10 +9,10 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc) : sils_port_id_(sils_port_id), i2c_address_(i2c_address), obc_(obc) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - sim_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = OBC_COM_UART_MODE::SILS; obc_->I2cConnectPort(sils_port_id_, i2c_address_); #endif } @@ -21,13 +21,13 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), i2c_address_(i2c_address), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = OBC_COM_UART_MODE::HILS; int ret = hils_port_manager_->I2cTargetConnectComPort(hils_port_id_); if (ret != 0) { std::cout << "Error: ObcI2cTargetCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif } @@ -36,13 +36,13 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int const unsigned char i2c_address, OBC* obc, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), i2c_address_(i2c_address), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = OBC_COM_UART_MODE::HILS; int ret = hils_port_manager_->I2cTargetConnectComPort(hils_port_id_); if (ret != 0) { std::cout << "Error: ObcI2cTargetCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - sim_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = OBC_COM_UART_MODE::SILS; obc_->I2cConnectPort(sils_port_id_, i2c_address_); #endif } @@ -51,7 +51,7 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(ObcI2cTargetCommuni : sils_port_id_(obj.sils_port_id_), hils_port_id_(obj.hils_port_id_), i2c_address_(obj.i2c_address_), - sim_mode_(obj.sim_mode_), + simulation_mode_(obj.simulation_mode_), obc_(obj.obc_), hils_port_manager_(obj.hils_port_manager_) { obj.is_moved_ = true; @@ -63,7 +63,7 @@ ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { if (is_moved_ == true) return; // prevent double freeing of memory int ret; - switch (sim_mode_) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: @@ -88,15 +88,15 @@ ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { } } -void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char len) { - switch (sim_mode_) { +void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char length) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - obc_->I2cComponentReadRegister(sils_port_id_, i2c_address_, reg_addr, data, len); + obc_->I2cComponentReadRegister(sils_port_id_, i2c_address_, reg_addr, data, length); break; case OBC_COM_UART_MODE::HILS: - hils_port_manager_->I2cTargetReadRegister(hils_port_id_, reg_addr, data, len); + hils_port_manager_->I2cTargetReadRegister(hils_port_id_, reg_addr, data, length); break; default: // NOT REACHED @@ -104,15 +104,15 @@ void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char reg_addr, u } } -void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { - switch (sim_mode_) { +void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char length) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - obc_->I2cComponentWriteRegister(sils_port_id_, i2c_address_, reg_addr, data, len); + obc_->I2cComponentWriteRegister(sils_port_id_, i2c_address_, reg_addr, data, length); break; case OBC_COM_UART_MODE::HILS: - hils_port_manager_->I2cTargetWriteRegister(hils_port_id_, reg_addr, data, len); + hils_port_manager_->I2cTargetWriteRegister(hils_port_id_, reg_addr, data, length); break; default: // NOT REACHED @@ -120,15 +120,15 @@ void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char reg_addr, } } -void ObcI2cTargetCommunicationBase::ReadCommand(unsigned char* data, const unsigned char len) { - switch (sim_mode_) { +void ObcI2cTargetCommunicationBase::ReadCommand(unsigned char* data, const unsigned char length) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - obc_->I2cComponentReadCommand(sils_port_id_, i2c_address_, data, len); + obc_->I2cComponentReadCommand(sils_port_id_, i2c_address_, data, length); break; case OBC_COM_UART_MODE::HILS: - hils_port_manager_->I2cTargetReadCommand(hils_port_id_, data, len); + hils_port_manager_->I2cTargetReadCommand(hils_port_id_, data, length); break; default: // NOT REACHED @@ -137,22 +137,22 @@ void ObcI2cTargetCommunicationBase::ReadCommand(unsigned char* data, const unsig } int ObcI2cTargetCommunicationBase::ReceiveCommand() { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cTargetReceive(hils_port_id_); } -int ObcI2cTargetCommunicationBase::SendTelemetry(const unsigned char len) { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; - return hils_port_manager_->I2cTargetSend(hils_port_id_, len); +int ObcI2cTargetCommunicationBase::SendTelemetry(const unsigned char length) { + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + return hils_port_manager_->I2cTargetSend(hils_port_id_, length); } int ObcI2cTargetCommunicationBase::GetStoredFrameCounter() { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cTargetGetStoredFrameCounter(hils_port_id_); } int ObcI2cTargetCommunicationBase::StoreTelemetry(const unsigned int stored_frame_num, const unsigned char tlm_size) { - if (sim_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; int additional_frame_num = stored_frame_num - GetStoredFrameCounter(); if (additional_frame_num <= 0) return -1; diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index fda5f51e2..5d4bf4fa4 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -61,24 +61,24 @@ class ObcI2cTargetCommunicationBase { * @brief Read register of I2C port * @param [in] reg_addr: Address of the target register * @param [out] data: Buffer to store the read data - * @param [in] len: Length of the data + * @param [in] length: Length of the data */ - void ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char len); + void ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char length); /** * @fn WriteRegister * @brief Read register of I2C port * @param [in] reg_addr: Address of the target register * @param [in] data: Write data - * @param [in] len: Length of the data + * @param [in] length: Length of the data */ - void WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char len); + void WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char length); /** * @fn ReadCommand * @brief Read command from I2C controller * @param [out] data: Buffer to store the read command data - * @param [in] len: Length of the data + * @param [in] length: Length of the data */ - void ReadCommand(unsigned char* data, const unsigned char len); + void ReadCommand(unsigned char* data, const unsigned char length); /** * @fn ReceiveCommand * @brief Receive command (HILS only) @@ -88,10 +88,10 @@ class ObcI2cTargetCommunicationBase { /** * @fn SendTelemetry * @brief Send Telemetry (HILS only) - * @param [in] len: Data length to write + * @param [in] length: Data length to write * @note This wraps I2cTargetSend in HilsPortManager */ - int SendTelemetry(const unsigned char len); + int SendTelemetry(const unsigned char length); /** * @fn GetStoredFrameCounter * @brief Return stored frame count (HILS only) @@ -115,7 +115,7 @@ class ObcI2cTargetCommunicationBase { unsigned char i2c_address_; //!< I2C address for the target bool is_moved_ = false; //!< Flag to show the object is copied or not - OBC_COM_UART_MODE sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode + OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode OBC* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index 7b7f272fc..dac7d3edd 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -9,57 +9,57 @@ ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - sim_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = OBC_COM_UART_MODE::SILS; #endif - tx_buf_size_ = kDefaultBufferSize; - rx_buf_size_ = kDefaultBufferSize; + tx_buffer_size_ = kDefaultBufferSize; + rx_buffer_size_ = kDefaultBufferSize; InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, const int tx_buf_size, const int rx_buf_size, OBC* obc) - : sils_port_id_(sils_port_id), tx_buf_size_(tx_buf_size), rx_buf_size_(rx_buf_size), obc_(obc) { +ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, const int tx_buffer_size, const int rx_buffer_size, OBC* obc) + : sils_port_id_(sils_port_id), tx_buffer_size_(tx_buffer_size), rx_buffer_size_(rx_buffer_size), obc_(obc) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - sim_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = OBC_COM_UART_MODE::SILS; #endif - if (tx_buf_size_ > kDefaultBufferSize) tx_buf_size_ = kDefaultBufferSize; - if (rx_buf_size_ > kDefaultBufferSize) rx_buf_size_ = kDefaultBufferSize; + if (tx_buffer_size_ > kDefaultBufferSize) tx_buffer_size_ = kDefaultBufferSize; + if (rx_buffer_size_ > kDefaultBufferSize) rx_buffer_size_ = kDefaultBufferSize; InitializeObcComBase(); } ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = OBC_COM_UART_MODE::HILS; #else - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif - tx_buf_size_ = kDefaultBufferSize; - rx_buf_size_ = kDefaultBufferSize; + tx_buffer_size_ = kDefaultBufferSize; + rx_buffer_size_ = kDefaultBufferSize; InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buf_size, - const int rx_buf_size, HilsPortManager* hils_port_manager) +ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buffer_size, + const int rx_buffer_size, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), - tx_buf_size_(tx_buf_size), - rx_buf_size_(rx_buf_size), + tx_buffer_size_(tx_buffer_size), + rx_buffer_size_(rx_buffer_size), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = OBC_COM_UART_MODE::HILS; #else - sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif - if (tx_buf_size_ > kDefaultBufferSize) tx_buf_size_ = kDefaultBufferSize; - if (rx_buf_size_ > kDefaultBufferSize) rx_buf_size_ = kDefaultBufferSize; + if (tx_buffer_size_ > kDefaultBufferSize) tx_buffer_size_ = kDefaultBufferSize; + if (rx_buffer_size_ > kDefaultBufferSize) rx_buffer_size_ = kDefaultBufferSize; InitializeObcComBase(); } @@ -67,19 +67,19 @@ ObcCommunicationBase::ObcCommunicationBase(const int sils_port_id, OBC* obc, con HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), baud_rate_(baud_rate), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - sim_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = OBC_COM_UART_MODE::HILS; #else - sim_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = OBC_COM_UART_MODE::SILS; #endif - tx_buf_size_ = kDefaultBufferSize; - rx_buf_size_ = kDefaultBufferSize; + tx_buffer_size_ = kDefaultBufferSize; + rx_buffer_size_ = kDefaultBufferSize; InitializeObcComBase(); } ObcCommunicationBase::~ObcCommunicationBase() { if (is_connected_ == false) return; int ret; - switch (sim_mode_) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: std::cout << "Error: ObcCommunication CloseComPort MODE_ERROR\n"; break; @@ -103,11 +103,11 @@ ObcCommunicationBase::~ObcCommunicationBase() { void ObcCommunicationBase::InitializeObcComBase() { int ret; - switch (sim_mode_) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - ret = obc_->ConnectComPort(sils_port_id_, tx_buf_size_, rx_buf_size_); + ret = obc_->ConnectComPort(sils_port_id_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Already connected: ObcCommunication ConnectComPort ID:" << sils_port_id_ << "\n"; is_connected_ = false; @@ -116,7 +116,7 @@ void ObcCommunicationBase::InitializeObcComBase() { } break; case OBC_COM_UART_MODE::HILS: - ret = hils_port_manager_->UartConnectComPort(hils_port_id_, baud_rate_, tx_buf_size_, rx_buf_size_); + ret = hils_port_manager_->UartConnectComPort(hils_port_id_, baud_rate_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Error: ObcCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; is_connected_ = false; @@ -131,13 +131,13 @@ void ObcCommunicationBase::InitializeObcComBase() { } int ObcCommunicationBase::ReceiveCommand(const int offset, const int rec_size) { - if (sim_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; - if (offset > rx_buf_size_) return -1; - if (offset + rec_size > rx_buf_size_) return -1; + if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; + if (offset > rx_buffer_size_) return -1; + if (offset + rec_size > rx_buffer_size_) return -1; rx_buffer_.resize(rec_size); int ret; - switch (sim_mode_) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::SILS: ret = obc_->ReceivedByCompo(sils_port_id_, &rx_buffer_.front(), offset, rec_size); if (ret == 0) return 0; // No read data @@ -153,12 +153,12 @@ int ObcCommunicationBase::ReceiveCommand(const int offset, const int rec_size) { } } int ObcCommunicationBase::SendTelemetry(const int offset) { - if (sim_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; + if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; int tlm_size = GenerateTelemetry(); - if (offset > rx_buf_size_) return -1; - if (offset + tlm_size > rx_buf_size_) return -1; + if (offset > rx_buffer_size_) return -1; + if (offset + tlm_size > rx_buffer_size_) return -1; - switch (sim_mode_) { + switch (simulation_mode_) { case OBC_COM_UART_MODE::SILS: obc_->SendFromCompo(sils_port_id_, &tx_buffer_.front(), offset, tlm_size); return 0; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 8f2529ab0..f9c96c170 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -40,11 +40,11 @@ class ObcCommunicationBase { * @fn ObcCommunicationBase * @brief Constructor for SILS mode * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode - * @param [in] tx_buf_size: TX (Component to OBC) buffer size - * @param [in] rx_buf_size: RX (OBC to Component) buffer size + * @param [in] tx_buffer_size: TX (Component to OBC) buffer size + * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] obc: The communication target OBC */ - ObcCommunicationBase(const int sils_port_id, const int tx_buf_size, const int rx_buf_size, OBC* obc); + ObcCommunicationBase(const int sils_port_id, const int tx_buffer_size, const int rx_buffer_size, OBC* obc); /** * @fn ObcCommunicationBase * @brief Constructor for HILS mode @@ -59,11 +59,11 @@ class ObcCommunicationBase { * @brief Constructor for HILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port - * @param [in] tx_buf_size: TX (Component to OBC) buffer size - * @param [in] rx_buf_size: RX (OBC to Component) buffer size + * @param [in] tx_buffer_size: TX (Component to OBC) buffer size + * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] hils_port_manager: HILS port manager */ - ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buf_size, const int rx_buf_size, + ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buffer_size, const int rx_buffer_size, HilsPortManager* hils_port_manager); /** * @fn ObcCommunicationBase @@ -100,11 +100,11 @@ class ObcCommunicationBase { int sils_port_id_; //!< Port ID for SILS int hils_port_id_; //!< Port ID for HILS int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 - int tx_buf_size_; //!< TX (Component to OBC) buffer size - int rx_buf_size_; //!< RX (OBC to Component) buffer size + int tx_buffer_size_; //!< TX (Component to OBC) buffer size + int rx_buffer_size_; //!< RX (OBC to Component) buffer size bool is_connected_ = false; // Connection flag - OBC_COM_UART_MODE sim_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode + OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode OBC* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager diff --git a/src/components/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp index b9c7e84e1..9f0981a42 100644 --- a/src/components/examples/example_i2c_controller_for_hils.cpp +++ b/src/components/examples/example_i2c_controller_for_hils.cpp @@ -5,9 +5,9 @@ #include "example_i2c_controller_for_hils.hpp" ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, - const unsigned int baud_rate, const unsigned int tx_buf_size, const unsigned int rx_buf_size, + const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) - : Component(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buf_size, rx_buf_size, hils_port_manager) {} + : Component(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buffer_size, rx_buffer_size, hils_port_manager) {} ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index ee4a96d37..05258ceab 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -27,12 +27,12 @@ class ExampleI2cControllerForHils : public Component, public I2cControllerCommun * @param [in] clock_gen: Clock generator * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port - * @param [in] tx_buf_size: TX (Controller to Target) buffer size - * @param [in] rx_buf_size: RX (Target to Controller) buffer size + * @param [in] tx_buffer_size: TX (Controller to Target) buffer size + * @param [in] rx_buffer_size: RX (Target to Controller) buffer size * @param [in] hils_port_manager: HILS port manager */ ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, - const unsigned int tx_buf_size, const unsigned int rx_buf_size, HilsPortManager* hils_port_manager); + const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cControllerForHils * @brief Destructor diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index 83743ff23..c1bee3a5c 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -7,11 +7,11 @@ SCIPort::SCIPort() : SCIPort(kDefaultBufferSize, kDefaultBufferSize) {} -SCIPort::SCIPort(int rx_buf_size, int tx_buf_size) { - if (rx_buf_size <= 0) rx_buf_size = kDefaultBufferSize; - if (tx_buf_size <= 0) tx_buf_size = kDefaultBufferSize; - rxb_ = new RingBuffer(rx_buf_size); - txb_ = new RingBuffer(tx_buf_size); +SCIPort::SCIPort(int rx_buffer_size, int tx_buffer_size) { + if (rx_buffer_size <= 0) rx_buffer_size = kDefaultBufferSize; + if (tx_buffer_size <= 0) tx_buffer_size = kDefaultBufferSize; + rxb_ = new RingBuffer(rx_buffer_size); + txb_ = new RingBuffer(tx_buffer_size); } SCIPort::~SCIPort() { diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 4fc73a682..59a47a8b2 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -24,10 +24,10 @@ class SCIPort { /** * @fn SCIPort * @brief Constructor - * @param [in] rx_buf_size: RX(Component -> OBC) buffer size - * @param [in] tx_buf_size: TX(OBC -> Component) buffer size + * @param [in] rx_buffer_size: RX(Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX(OBC -> Component) buffer size */ - SCIPort(int rx_buf_size, int tx_buf_size); + SCIPort(int rx_buffer_size, int tx_buffer_size); /** * @fn ~SCIPort * @brief Destructor diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index a54289e91..b93665f8e 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -21,12 +21,12 @@ void OBC::Initialize() {} void OBC::MainRoutine(int count) { UNUSED(count); } -int OBC::ConnectComPort(int port_id, int tx_buf_size, int rx_buf_size) { +int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { if (com_ports_[port_id] != nullptr) { // Port already used return -1; } - com_ports_[port_id] = new SCIPort(tx_buf_size, rx_buf_size); + com_ports_[port_id] = new SCIPort(tx_buffer_size, rx_buffer_size); return 0; } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 8da989776..e4ef7bf86 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -55,11 +55,11 @@ class OBC : public Component { * @fn ConnectComPort * @brief Connect UART communication port between OBC and a component * @param [in] port_id: Port ID - * @param [in] tx_buf_size: TX (OBC -> Component) buffer size - * @param [in] rx_buf_size: RX (Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX (OBC -> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size * @return -1: error, 0: success */ - virtual int ConnectComPort(int port_id, int tx_buf_size, int rx_buf_size); + virtual int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size); /** * @fn ConnectComPort * @brief Close UART communication port between OBC and a component diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index 02282af39..5a2461651 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -61,12 +61,12 @@ void OBC_C2A::MainRoutine(int count) { } // Override functions -int OBC_C2A::ConnectComPort(int port_id, int tx_buf_size, int rx_buf_size) { +int OBC_C2A::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { if (com_ports_c2a_[port_id] != nullptr) { // Port already used return -1; } - com_ports_c2a_[port_id] = new SCIPort(tx_buf_size, rx_buf_size); + com_ports_c2a_[port_id] = new SCIPort(tx_buffer_size, rx_buffer_size); return 0; } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 7ede0d2c9..1f1164bd1 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -49,11 +49,11 @@ class OBC_C2A : public OBC { * @fn ConnectComPort * @brief Connect UART communication port between OBC and a component * @param [in] port_id: Port ID - * @param [in] tx_buf_size: TX (OBC -> Component) buffer size - * @param [in] rx_buf_size: RX (Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX (OBC -> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size * @return -1: error, 0: success */ - int ConnectComPort(int port_id, int tx_buf_size, int rx_buf_size) override; + int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) override; /** * @fn ConnectComPort * @brief Close UART communication port between OBC and a component diff --git a/src/simulation/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp index 65ce0f9ca..3b641709b 100644 --- a/src/simulation/hils/hils_port_manager.cpp +++ b/src/simulation/hils/hils_port_manager.cpp @@ -14,23 +14,23 @@ HilsPortManager::HilsPortManager() {} HilsPortManager::~HilsPortManager() {} // UART Communication port functions -int HilsPortManager::UartConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buf_size, unsigned int rx_buf_size) { +int HilsPortManager::UartConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size) { #ifdef USE_HILS if (uart_com_ports_[port_id] != nullptr) { printf("Error: Port is already used\n"); return -1; } - if (baud_rate <= 0 || tx_buf_size <= 0 || rx_buf_size <= 0) { + if (baud_rate <= 0 || tx_buffer_size <= 0 || rx_buffer_size <= 0) { printf("Error: Illegal parameter\n"); return -1; } - uart_com_ports_[port_id] = new HilsUartPort(port_id, baud_rate, tx_buf_size, rx_buf_size); + uart_com_ports_[port_id] = new HilsUartPort(port_id, baud_rate, tx_buffer_size, rx_buffer_size); return 0; #else UNUSED(port_id); UNUSED(baud_rate); - UNUSED(tx_buf_size); - UNUSED(rx_buf_size); + UNUSED(tx_buffer_size); + UNUSED(rx_buffer_size); return -1; #endif @@ -242,8 +242,8 @@ int HilsPortManager::I2cTargetGetStoredFrameCounter(unsigned int port_id) { } // I2C Controller Communication port functions -int HilsPortManager::I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buf_size, unsigned int rx_buf_size) { - return UartConnectComPort(port_id, baud_rate, tx_buf_size, rx_buf_size); +int HilsPortManager::I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size) { + return UartConnectComPort(port_id, baud_rate, tx_buffer_size, rx_buffer_size); } int HilsPortManager::I2cControllerCloseComPort(unsigned int port_id) { return UartCloseComPort(port_id); } diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index e058a0d19..f48492982 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -35,10 +35,10 @@ class HilsPortManager { * @brief Connect UART port * @param [in] port_id: COM port ID * @param [in] baud_rate: Baud rate ex 9600, 115200 - * @param [in] tx_buf_size: TX buffer size - * @param [in] rx_buf_size: RX buffer size + * @param [in] tx_buffer_size: TX buffer size + * @param [in] rx_buffer_size: RX buffer size */ - virtual int UartConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buf_size, unsigned int rx_buf_size); + virtual int UartConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size); /** * @fn UartCloseComPort * @brief Close UART port @@ -131,10 +131,10 @@ class HilsPortManager { * @brief Connect I2C controller side device on the COM port * @param [in] port_id: COM port ID * @param [in] baud_rate: Baud rate ex 9600, 115200 - * @param [in] tx_buf_size: TX buffer size - * @param [in] rx_buf_size: RX buffer size + * @param [in] tx_buffer_size: TX buffer size + * @param [in] rx_buffer_size: RX buffer size */ - virtual int I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buf_size, unsigned int rx_buf_size); + virtual int I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size); /** * @fn I2cControllerCloseComPort * @brief Close I2C controller side device on the COM port From 94d91e739d03fda2f77413f0a4d64689f430ad3f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:11:05 +0100 Subject: [PATCH 0733/1086] Add unsigned --- src/components/base/i2c_controller.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 973954407..87a5aa3b4 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -56,7 +56,7 @@ class I2cControllerCommunicationBase { private: unsigned int hils_port_id_; //!< ID of HILS communication port - int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 + unsigned int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 unsigned int tx_buffer_size_; //!< TX (Controller to Target) buffer size unsigned int rx_buffer_size_; //!< RX (Target to Controller) buffer size OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode (SILS or HILS) From 7319d78c31ca78a6ea49b81d4b9d8f42cd699b94 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:12:27 +0100 Subject: [PATCH 0734/1086] Rename I2cControllerCommunicationBase to I2cController --- src/components/base/i2c_controller.cpp | 11 +++++------ src/components/base/i2c_controller.hpp | 14 +++++++------- .../examples/example_i2c_controller_for_hils.cpp | 6 +++--- .../examples/example_i2c_controller_for_hils.hpp | 2 +- 4 files changed, 16 insertions(+), 17 deletions(-) diff --git a/src/components/base/i2c_controller.cpp b/src/components/base/i2c_controller.cpp index 6ef2b7fbc..2b3c47037 100644 --- a/src/components/base/i2c_controller.cpp +++ b/src/components/base/i2c_controller.cpp @@ -6,9 +6,8 @@ #include -I2cControllerCommunicationBase::I2cControllerCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, - const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, - HilsPortManager* hils_port_manager) +I2cController::I2cController(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), tx_buffer_size_(tx_buffer_size), @@ -26,7 +25,7 @@ I2cControllerCommunicationBase::I2cControllerCommunicationBase(const unsigned in #endif } -I2cControllerCommunicationBase::~I2cControllerCommunicationBase() { +I2cController::~I2cController() { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return; int ret = hils_port_manager_->I2cControllerCloseComPort(hils_port_id_); @@ -35,12 +34,12 @@ I2cControllerCommunicationBase::~I2cControllerCommunicationBase() { } } -int I2cControllerCommunicationBase::ReceiveTelemetry(const unsigned char length) { +int I2cController::ReceiveTelemetry(const unsigned char length) { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cControllerReceive(hils_port_id_, &rx_buffer_.front(), 0, length); } -int I2cControllerCommunicationBase::SendCommand(const unsigned char length) { +int I2cController::SendCommand(const unsigned char length) { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cControllerSend(hils_port_id_, &tx_buffer_.front(), 0, length); } diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 87a5aa3b4..7475b91db 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -10,16 +10,16 @@ #include "uart_communication_with_obc.hpp" /** - * @class I2cControllerCommunicationBase + * @class I2cController * @brief This class simulates the I2C Controller communication with the I2C Target. * @note Generally, I2C controller side is OBC, and components are target side. * The main purpose is to validate the emulated I2C Target component in the HILS test. * This class works only HILS mode */ -class I2cControllerCommunicationBase { +class I2cController { public: /** - * @fn I2cControllerCommunicationBase + * @fn I2cController * @brief Constructor * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port @@ -27,13 +27,13 @@ class I2cControllerCommunicationBase { * @param [in] rx_buffer_size: RX (Target to Controller) buffer size * @param [in] hils_port_manager: HILS port manager */ - I2cControllerCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, - const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); + I2cController(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, + HilsPortManager* hils_port_manager); /** - * @fn ~I2cControllerCommunicationBase + * @fn ~I2cController * @brief Destructor */ - ~I2cControllerCommunicationBase(); + ~I2cController(); protected: /** diff --git a/src/components/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp index 9f0981a42..8e3bb3e94 100644 --- a/src/components/examples/example_i2c_controller_for_hils.cpp +++ b/src/components/examples/example_i2c_controller_for_hils.cpp @@ -5,9 +5,9 @@ #include "example_i2c_controller_for_hils.hpp" ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, - const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, - HilsPortManager* hils_port_manager) - : Component(prescaler, clock_gen), I2cControllerCommunicationBase(hils_port_id, baud_rate, tx_buffer_size, rx_buffer_size, hils_port_manager) {} + const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) + : Component(prescaler, clock_gen), I2cController(hils_port_id, baud_rate, tx_buffer_size, rx_buffer_size, hils_port_manager) {} ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 05258ceab..1363a9e82 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -18,7 +18,7 @@ * SC18IM700 Data Sheet: https://www.nxp.com/docs/en/data-sheet/SC18IM700.pdf * telemetry size = 5 bytes(ASCII) */ -class ExampleI2cControllerForHils : public Component, public I2cControllerCommunicationBase { +class ExampleI2cControllerForHils : public Component, public I2cController { public: /** * @fn ExampleI2cControllerForHils From 074452c648f525c2d30aedffff8a673e96b840ee Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:18:47 +0100 Subject: [PATCH 0735/1086] Rename function arguments --- .../i2c_target_communication_with_obc.cpp | 32 +++++++++---------- .../i2c_target_communication_with_obc.hpp | 10 +++--- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index 37ed18fa6..441316da2 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -47,16 +47,16 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int #endif } -ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& obj) noexcept - : sils_port_id_(obj.sils_port_id_), - hils_port_id_(obj.hils_port_id_), - i2c_address_(obj.i2c_address_), - simulation_mode_(obj.simulation_mode_), - obc_(obj.obc_), - hils_port_manager_(obj.hils_port_manager_) { - obj.is_moved_ = true; - obj.obc_ = nullptr; - obj.hils_port_manager_ = nullptr; +ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& object) noexcept + : sils_port_id_(object.sils_port_id_), + hils_port_id_(object.hils_port_id_), + i2c_address_(object.i2c_address_), + simulation_mode_(object.simulation_mode_), + obc_(object.obc_), + hils_port_manager_(object.hils_port_manager_) { + object.is_moved_ = true; + object.obc_ = nullptr; + object.hils_port_manager_ = nullptr; } ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { @@ -88,15 +88,15 @@ ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { } } -void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char length) { +void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char register_address, unsigned char* data, const unsigned char length) { switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - obc_->I2cComponentReadRegister(sils_port_id_, i2c_address_, reg_addr, data, length); + obc_->I2cComponentReadRegister(sils_port_id_, i2c_address_, register_address, data, length); break; case OBC_COM_UART_MODE::HILS: - hils_port_manager_->I2cTargetReadRegister(hils_port_id_, reg_addr, data, length); + hils_port_manager_->I2cTargetReadRegister(hils_port_id_, register_address, data, length); break; default: // NOT REACHED @@ -104,15 +104,15 @@ void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char reg_addr, u } } -void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char length) { +void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char register_address, const unsigned char* data, const unsigned char length) { switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; case OBC_COM_UART_MODE::SILS: - obc_->I2cComponentWriteRegister(sils_port_id_, i2c_address_, reg_addr, data, length); + obc_->I2cComponentWriteRegister(sils_port_id_, i2c_address_, register_address, data, length); break; case OBC_COM_UART_MODE::HILS: - hils_port_manager_->I2cTargetWriteRegister(hils_port_id_, reg_addr, data, length); + hils_port_manager_->I2cTargetWriteRegister(hils_port_id_, register_address, data, length); break; default: // NOT REACHED diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 5d4bf4fa4..0c82250f5 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -48,7 +48,7 @@ class ObcI2cTargetCommunicationBase { * @fn ObcI2cTargetCommunicationBase * @brief Prevent double freeing of memory when this class is copied */ - ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& obj) noexcept; + ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& object) noexcept; /** * @fn ~ObcI2cTargetCommunicationBase * @brief Destructor @@ -59,19 +59,19 @@ class ObcI2cTargetCommunicationBase { /** * @fn ReadRegister * @brief Read register of I2C port - * @param [in] reg_addr: Address of the target register + * @param [in] register_address: Address of the target register * @param [out] data: Buffer to store the read data * @param [in] length: Length of the data */ - void ReadRegister(const unsigned char reg_addr, unsigned char* data, const unsigned char length); + void ReadRegister(const unsigned char register_address, unsigned char* data, const unsigned char length); /** * @fn WriteRegister * @brief Read register of I2C port - * @param [in] reg_addr: Address of the target register + * @param [in] register_address: Address of the target register * @param [in] data: Write data * @param [in] length: Length of the data */ - void WriteRegister(const unsigned char reg_addr, const unsigned char* data, const unsigned char length); + void WriteRegister(const unsigned char register_address, const unsigned char* data, const unsigned char length); /** * @fn ReadCommand * @brief Read command from I2C controller From 3e08d6c8f6e06c0f4f3a8b19d82b5ee2a081d82a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:21:59 +0100 Subject: [PATCH 0736/1086] Rename I2cTargetCommunicationBase to I2cTargetCommunicationWithObc --- .../i2c_target_communication_with_obc.cpp | 24 +++++++++---------- .../i2c_target_communication_with_obc.hpp | 24 +++++++++---------- .../examples/example_i2c_target_for_hils.cpp | 2 +- .../examples/example_i2c_target_for_hils.hpp | 2 +- 4 files changed, 26 insertions(+), 26 deletions(-) diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index 441316da2..63a92f096 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -6,7 +6,7 @@ #include -ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc) +I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc) : sils_port_id_(sils_port_id), i2c_address_(i2c_address), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; @@ -17,7 +17,7 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int #endif } -ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int hils_port_id, const unsigned char i2c_address, +I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int hils_port_id, const unsigned char i2c_address, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), i2c_address_(i2c_address), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS @@ -32,7 +32,7 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int #endif } -ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int sils_port_id, const unsigned int hils_port_id, +I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OBC* obc, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), i2c_address_(i2c_address), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS @@ -47,7 +47,7 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(const unsigned int #endif } -ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& object) noexcept +I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(I2cTargetCommunicationWithObc&& object) noexcept : sils_port_id_(object.sils_port_id_), hils_port_id_(object.hils_port_id_), i2c_address_(object.i2c_address_), @@ -59,7 +59,7 @@ ObcI2cTargetCommunicationBase::ObcI2cTargetCommunicationBase(ObcI2cTargetCommuni object.hils_port_manager_ = nullptr; } -ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { +I2cTargetCommunicationWithObc::~I2cTargetCommunicationWithObc() { if (is_moved_ == true) return; // prevent double freeing of memory int ret; @@ -88,7 +88,7 @@ ObcI2cTargetCommunicationBase::~ObcI2cTargetCommunicationBase() { } } -void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char register_address, unsigned char* data, const unsigned char length) { +void I2cTargetCommunicationWithObc::ReadRegister(const unsigned char register_address, unsigned char* data, const unsigned char length) { switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; @@ -104,7 +104,7 @@ void ObcI2cTargetCommunicationBase::ReadRegister(const unsigned char register_ad } } -void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char register_address, const unsigned char* data, const unsigned char length) { +void I2cTargetCommunicationWithObc::WriteRegister(const unsigned char register_address, const unsigned char* data, const unsigned char length) { switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; @@ -120,7 +120,7 @@ void ObcI2cTargetCommunicationBase::WriteRegister(const unsigned char register_a } } -void ObcI2cTargetCommunicationBase::ReadCommand(unsigned char* data, const unsigned char length) { +void I2cTargetCommunicationWithObc::ReadCommand(unsigned char* data, const unsigned char length) { switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: break; @@ -136,22 +136,22 @@ void ObcI2cTargetCommunicationBase::ReadCommand(unsigned char* data, const unsig } } -int ObcI2cTargetCommunicationBase::ReceiveCommand() { +int I2cTargetCommunicationWithObc::ReceiveCommand() { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cTargetReceive(hils_port_id_); } -int ObcI2cTargetCommunicationBase::SendTelemetry(const unsigned char length) { +int I2cTargetCommunicationWithObc::SendTelemetry(const unsigned char length) { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cTargetSend(hils_port_id_, length); } -int ObcI2cTargetCommunicationBase::GetStoredFrameCounter() { +int I2cTargetCommunicationWithObc::GetStoredFrameCounter() { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; return hils_port_manager_->I2cTargetGetStoredFrameCounter(hils_port_id_); } -int ObcI2cTargetCommunicationBase::StoreTelemetry(const unsigned int stored_frame_num, const unsigned char tlm_size) { +int I2cTargetCommunicationWithObc::StoreTelemetry(const unsigned int stored_frame_num, const unsigned char tlm_size) { if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; int additional_frame_num = stored_frame_num - GetStoredFrameCounter(); if (additional_frame_num <= 0) return -1; diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 0c82250f5..32041489f 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -11,30 +11,30 @@ #include "uart_communication_with_obc.hpp" /** - * @class ObcI2cTargetCommunicationBase + * @class I2cTargetCommunicationWithObc * @brief Base class for I2C communication as target side with OBC flight software * @note Generally, components are the target side of I2C (OBC is the controller side). */ -class ObcI2cTargetCommunicationBase { +class I2cTargetCommunicationWithObc { public: /** - * @fn ObcI2cTargetCommunicationBase + * @fn I2cTargetCommunicationWithObc * @brief Constructor for SILS mode * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode * @param [in] i2c_address: I2C address for the target * @param [in] obc: The communication target OBC */ - ObcI2cTargetCommunicationBase(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc); + I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc); /** - * @fn ObcI2cTargetCommunicationBase + * @fn I2cTargetCommunicationWithObc * @brief Constructor for HILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] i2c_address: I2C address for the target * @param [in] hils_port_manager: HILS port manager */ - ObcI2cTargetCommunicationBase(const unsigned int hils_port_id, const unsigned char i2c_address, HilsPortManager* hils_port_manager); + I2cTargetCommunicationWithObc(const unsigned int hils_port_id, const unsigned char i2c_address, HilsPortManager* hils_port_manager); /** - * @fn ObcI2cTargetCommunicationBase + * @fn I2cTargetCommunicationWithObc * @brief Constructor for both SILS and HILS mode * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode * @param [in] hils_port_id: ID of HILS communication port @@ -42,18 +42,18 @@ class ObcI2cTargetCommunicationBase { * @param [in] obc: The communication target OBC * @param [in] hils_port_manager: HILS port manager */ - ObcI2cTargetCommunicationBase(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OBC* obc, + I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OBC* obc, HilsPortManager* hils_port_manager); /** - * @fn ObcI2cTargetCommunicationBase + * @fn I2cTargetCommunicationWithObc * @brief Prevent double freeing of memory when this class is copied */ - ObcI2cTargetCommunicationBase(ObcI2cTargetCommunicationBase&& object) noexcept; + I2cTargetCommunicationWithObc(I2cTargetCommunicationWithObc&& object) noexcept; /** - * @fn ~ObcI2cTargetCommunicationBase + * @fn ~I2cTargetCommunicationWithObc * @brief Destructor */ - ~ObcI2cTargetCommunicationBase(); + ~I2cTargetCommunicationWithObc(); protected: /** diff --git a/src/components/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp index 4bb0d020e..e2f0bab0e 100644 --- a/src/components/examples/example_i2c_target_for_hils.cpp +++ b/src/components/examples/example_i2c_target_for_hils.cpp @@ -7,7 +7,7 @@ ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) - : Component(prescaler, clock_gen), ObcI2cTargetCommunicationBase(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} + : Component(prescaler, clock_gen), I2cTargetCommunicationWithObc(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} ExampleI2cTargetForHils::~ExampleI2cTargetForHils() {} diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index c595f7303..1cd7ace2e 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -19,7 +19,7 @@ * Telemetry size = 5 bytes(ASCII) * Telemetry changes; ABCDE, BCDEF, ..., VWXYZ, ABCDE, ... */ -class ExampleI2cTargetForHils : public Component, public ObcI2cTargetCommunicationBase { +class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationWithObc { public: /** * @fn ExampleI2cTargetForHils From 8fe23f850c74fd6cc054bab6079c5f8977d55992 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:26:13 +0100 Subject: [PATCH 0737/1086] Rename function arguments --- src/components/base/interface_gpio_component.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/base/interface_gpio_component.hpp b/src/components/base/interface_gpio_component.hpp index 9f2885792..1dde12df7 100644 --- a/src/components/base/interface_gpio_component.hpp +++ b/src/components/base/interface_gpio_component.hpp @@ -22,9 +22,9 @@ class IGPIOCompo { * @fn GPIOStateChanged * @brief Pure virtual function called at the GPIO state is changed like interrupt function. * @param[in] port_id: GPIO port ID - * @param[in] isPosedge: Flag to express positive edge or not + * @param[in] is_positive_edge: Flag to express positive edge or not */ - virtual void GPIOStateChanged(int port_id, bool isPosedge) = 0; + virtual void GPIOStateChanged(const int port_id, const bool is_positive_edge) = 0; }; #endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_HPP_ From 59600a69d0b7730397e417c1c2ac4f03cebbbb6c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:33:16 +0100 Subject: [PATCH 0738/1086] Rename function arguments --- src/components/base/sensor.hpp | 24 +++++++++---------- .../base/sensor_template_functions.hpp | 15 ++++++------ 2 files changed, 20 insertions(+), 19 deletions(-) diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index a38a764f4..d1c7df589 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -26,14 +26,14 @@ class SensorBase { * @param [in] range_to_const_c: Output range limit to be constant output value at the component frame * @param [in] range_to_zero_c: Output range limit to be zero output value at the component frame * @param [in] bias_c: Constant bias noise at the component frame - * @param [in] nr_stddev_c: Standard deviation of normal random noise at the component frame - * @param [in] rw_stepwidth: Step width for random walk calculation [sec] - * @param [in] rw_stddev_c: Standard deviation of random wark at the component frame - * @param [in] rw_limit_c: Limit of random walk at the component frame + * @param [in] normal_random_standard_deviation_c: Standard deviation of normal random noise at the component frame + * @param [in] random_walk_step_width_s: Step width for random walk calculation [sec] + * @param [in] random_walk_standard_deviation_c: Standard deviation of random wark at the component frame + * @param [in] random_walk_limit_c: Limit of random walk at the component frame */ SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& nr_stddev_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c); + const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c); /** * @fn ~SensorBase * @brief Destructor @@ -50,12 +50,12 @@ class SensorBase { libra::Vector Measure(const libra::Vector true_value_c); private: - libra::Matrix scale_factor_; //!< Scale factor matrix - libra::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame - libra::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame - libra::Vector bias_c_; //!< Constant bias noise at the component frame - libra::NormalRand nrs_c_[N]; //!< Normal random - RandomWalk n_rw_c_; //!< Random Walk + libra::Matrix scale_factor_; //!< Scale factor matrix + libra::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame + libra::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame + libra::Vector bias_c_; //!< Constant bias noise at the component frame + libra::NormalRand normal_random_noise_c_[N]; //!< Normal random + RandomWalk random_walk_noise_c_; //!< Random Walk /** * @fn Clip diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index 072e0a2a0..f95a54dee 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -10,15 +10,16 @@ template SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& nr_stddev_c, double rw_stepwidth, - const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c) + const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, + const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, + const libra::Vector& random_walk_limit_c) : scale_factor_(scale_factor), range_to_const_c_(range_to_const_c), range_to_zero_c_(range_to_zero_c), bias_c_(bias_c), - n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c) { + random_walk_noise_c_(random_walk_step_width_s, random_walk_standard_deviation_c, random_walk_limit_c) { for (size_t i = 0; i < N; i++) { - nrs_c_[i].SetParameters(0.0, nr_stddev_c[i], global_randomization.MakeSeed()); + normal_random_noise_c_[i].SetParameters(0.0, normal_random_standard_deviation_c[i], global_randomization.MakeSeed()); } RangeCheck(); } @@ -32,10 +33,10 @@ libra::Vector SensorBase::Measure(const libra::Vector true_value_c) { calc_value_c = scale_factor_ * true_value_c; calc_value_c += bias_c_; for (size_t i = 0; i < N; ++i) { - calc_value_c[i] += n_rw_c_[i]; - calc_value_c[i] += nrs_c_[i]; + calc_value_c[i] += random_walk_noise_c_[i]; + calc_value_c[i] += normal_random_noise_c_[i]; } - ++n_rw_c_; // update Random Walk + ++random_walk_noise_c_; // update Random Walk return Clip(calc_value_c); } From a3ec6c2066acdb857c9dff187c1629b7de21b7b7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 26 Feb 2023 00:39:09 +0100 Subject: [PATCH 0739/1086] Fix comment --- src/components/base/uart_communication_with_obc.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index f9c96c170..41c333c48 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -101,8 +101,8 @@ class ObcCommunicationBase { int hils_port_id_; //!< Port ID for HILS int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 int tx_buffer_size_; //!< TX (Component to OBC) buffer size - int rx_buffer_size_; //!< RX (OBC to Component) buffer size - bool is_connected_ = false; // Connection flag + int rx_buffer_size_; //!< RX (OBC to Component) buffer size + bool is_connected_ = false; //!< Connection flag OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode From d967f3891272e406bb907f67b8545aedf8186198 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 09:58:16 +0100 Subject: [PATCH 0740/1086] Fix GetGeomagneticField --- src/components/real/aocs/magnetometer.cpp | 4 ++-- src/components/real/aocs/magnetorquer.cpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/geomagnetic_field.hpp | 8 ++++---- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index a9c19c5e1..ca6c17914 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -17,8 +17,8 @@ MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = q_b2c_.FrameConversion(magnet_->GetGeomagneticFieldneticField_b_nT()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + mag_c_ = q_b2c_.FrameConversion(magnet_->GetGeomagneticField_b_nT()); // Convert frame + mag_c_ = Measure(mag_c_); // Add noises } std::string MagSensor::GetLogHeader() const { diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 433736f0a..bd8fb6d0e 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -74,7 +74,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { // Frame conversion component to body mag_moment_b_ = q_c2b_.FrameConversion(mag_moment_c_); // Calc magnetic torque [Nm] - torque_b_ = OuterProduct(mag_moment_b_, knT2T * mag_env_->GetGeomagneticFieldneticField_b_nT()); + torque_b_ = OuterProduct(mag_moment_b_, knT2T * mag_env_->GetGeomagneticField_b_nT()); // Update Random Walk ++n_rw_c_; diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index caf70f7fc..5a62551c9 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -26,7 +26,7 @@ Vector<3> MagneticDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b void MagneticDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - CalcTorque_b_Nm(local_environment.GetGeomagneticField().GetGeomagneticFieldneticField_b_nT()); + CalcTorque_b_Nm(local_environment.GetGeomagneticField().GetGeomagneticField_b_nT()); } void MagneticDisturbance::CalcRMM() { diff --git a/src/environment/local/geomagnetic_field.hpp b/src/environment/local/geomagnetic_field.hpp index 049a614cd..a2e227e16 100644 --- a/src/environment/local/geomagnetic_field.hpp +++ b/src/environment/local/geomagnetic_field.hpp @@ -47,15 +47,15 @@ class GeomagneticField : public ILoggable { const libra::Quaternion quaternion_i2b); /** - * @fn GetGeomagneticFieldneticField_i_nT + * @fn GetGeomagneticField_i_nT * @brief Return magnetic field vector in the inertial frame [nT] */ - inline libra::Vector<3> GetGeomagneticFieldneticField_i_nT() const { return magnetic_field_i_nT_; } + inline libra::Vector<3> GetGeomagneticField_i_nT() const { return magnetic_field_i_nT_; } /** - * @fn GetGeomagneticFieldneticField_b_nT + * @fn GetGeomagneticField_b_nT * @brief Return magnetic field vector in the body fixed frame [nT] */ - inline libra::Vector<3> GetGeomagneticFieldneticField_b_nT() const { return magnetic_field_b_nT_; } + inline libra::Vector<3> GetGeomagneticField_b_nT() const { return magnetic_field_b_nT_; } // Override ILoggable /** From ae5099127f2ebc38f9466544728a6ca83ddf7bc6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 09:59:32 +0100 Subject: [PATCH 0741/1086] Fix IsValidRange --- src/library/math/matrix.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 24fade351..58635fb04 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -69,7 +69,7 @@ class Matrix { * @return Value of the target element */ inline T& operator()(size_t row, size_t column) { - if (!ISValidRange(row, column)) { + if (!IsValidRange(row, column)) { throw std::invalid_argument("Argument exceeds the range of matrix."); } return matrix_[row][column]; @@ -84,7 +84,7 @@ class Matrix { * @return Value of the target element */ inline const T& operator()(size_t row, size_t column) const { - if (!ISValidRange(row, column)) { + if (!IsValidRange(row, column)) { throw std::invalid_argument("Argument exceeds the range of matrix."); } return matrix_[row][column]; @@ -130,13 +130,13 @@ class Matrix { T matrix_[R][C]; //!< Array to save the elements /** - * @fn ISValidRange + * @fn IsValidRange * @brief Judge the target row/column number is in the range * @param [in] row: Target row number * @param [in] column: Target column number * @return True: row/column number is in the range */ - inline bool ISValidRange(size_t row, size_t column) { return (row < R && column < C); } + inline bool IsValidRange(size_t row, size_t column) { return (row < R && column < C); } }; /** From f158a56eb5594370650d510a3814e092d4744eec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:08:41 +0100 Subject: [PATCH 0742/1086] Fix comments --- src/library/math/matrix.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 58635fb04..5e32b985a 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -150,7 +150,7 @@ void FillUp(Matrix& m, const T& t); /** * @fn CalcTrace - * @brief Calculate and return the CalcTrace of matrix + * @brief Calculate and return the trace of matrix * @param [in] m: Target matrix * @return Trace of the matrix */ From a9905615399a1022cbd409d1f66a69739ec2d398 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:27:10 +0100 Subject: [PATCH 0743/1086] Rename SensorBase to Sensor --- src/components/base/initialize_sensor.hpp | 12 ++++++------ .../initialize_sensor_template_functions.hpp | 9 ++++----- src/components/base/sensor.hpp | 16 ++++++++-------- .../base/sensor_template_functions.hpp | 19 +++++++++---------- src/components/real/aocs/gnss_receiver.hpp | 2 +- src/components/real/aocs/gyro_sensor.cpp | 8 ++++---- src/components/real/aocs/gyro_sensor.hpp | 6 +++--- .../real/aocs/initialize_gyro_sensor.cpp | 8 ++++---- .../real/aocs/initialize_magnetometer.cpp | 8 ++++---- src/components/real/aocs/magnetometer.cpp | 8 ++++---- src/components/real/aocs/magnetometer.hpp | 6 +++--- 11 files changed, 50 insertions(+), 52 deletions(-) diff --git a/src/components/base/initialize_sensor.hpp b/src/components/base/initialize_sensor.hpp index 8aa1eab2b..573e9557d 100644 --- a/src/components/base/initialize_sensor.hpp +++ b/src/components/base/initialize_sensor.hpp @@ -1,6 +1,6 @@ /** * @file initialize_sensor.hpp - * @brief Initialize functions for SensorBase class + * @brief Initialize functions for Sensor class */ #ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_HPP_ @@ -9,17 +9,17 @@ #include "sensor.hpp" /** - * @fn ReadSensorBaseInformation - * @brief Read information from initialize file for SensorBase class - * @note It is recommended to use this function for all sensors inherits the SensorBase class + * @fn ReadSensorInformation + * @brief Read information from initialize file for Sensor class + * @note It is recommended to use this function for all sensors inherits the Sensor class * @param [in] file_name: Path to the initialize file * @param [in] step_width_s: Step width of component update [sec] * @param [in] component_name: Component name * @param [in] unit: Unit of the sensor */ template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, - const std::string unit = ""); +Sensor ReadSensorInformation(const std::string file_name, const double step_width_s, const std::string component_name, + const std::string unit = ""); #include "initialize_sensor_template_functions.hpp" diff --git a/src/components/base/initialize_sensor_template_functions.hpp b/src/components/base/initialize_sensor_template_functions.hpp index 3d7dcd2b6..6e0c275b4 100644 --- a/src/components/base/initialize_sensor_template_functions.hpp +++ b/src/components/base/initialize_sensor_template_functions.hpp @@ -1,6 +1,6 @@ /** * @file initialize_sensor_template_functions.hpp - * @brief Initialize functions for SensorBase class (template functions) + * @brief Initialize functions for Sensor class (template functions) */ #ifndef S2E_COMPONENTS_BASE_INITIALIZE_SENSOR_TEMPLATE_FUNCTIONS_HPP_ @@ -9,8 +9,7 @@ #include "library/initialize/initialize_file_access.hpp" template -SensorBase ReadSensorBaseInformation(const std::string file_name, const double step_width_s, const std::string component_name, - const std::string unit) { +Sensor ReadSensorInformation(const std::string file_name, const double step_width_s, const std::string component_name, const std::string unit) { IniAccess ini_file(file_name); std::string section = "SENSOR_BASE_" + component_name; @@ -45,8 +44,8 @@ SensorBase ReadSensorBaseInformation(const std::string file_name, const doubl double range_to_zero = ini_file.ReadDouble(section.c_str(), key_name.c_str()); libra::Vector range_to_zero_c{range_to_zero}; - SensorBase sensor_base(scale_factor_c, range_to_const_c, range_to_zero_c, constant_bias_c, normal_random_standard_deviation_c, step_width_s, - random_walk_standard_deviation_c, random_walk_limit_c); + Sensor sensor_base(scale_factor_c, range_to_const_c, range_to_zero_c, constant_bias_c, normal_random_standard_deviation_c, step_width_s, + random_walk_standard_deviation_c, random_walk_limit_c); return sensor_base; } diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index d1c7df589..a63d17093 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -12,15 +12,15 @@ #include /** - * @class SensorBase + * @class Sensor * @brief Base class for sensor emulation to add noises * @note All sensors should inherit this class */ template -class SensorBase { +class Sensor { public: /** - * @fn SensorBase + * @fn Sensor * @brief Constructor * @param [in] scale_factor: Scale factor matrix * @param [in] range_to_const_c: Output range limit to be constant output value at the component frame @@ -31,14 +31,14 @@ class SensorBase { * @param [in] random_walk_standard_deviation_c: Standard deviation of random wark at the component frame * @param [in] random_walk_limit_c: Limit of random walk at the component frame */ - SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, - const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c); + Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, + const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c); /** - * @fn ~SensorBase + * @fn ~Sensor * @brief Destructor */ - ~SensorBase(); + ~Sensor(); protected: /** diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index f95a54dee..5faf0bbbb 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -9,10 +9,9 @@ #include template -SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, - const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, - const libra::Vector& random_walk_limit_c) +Sensor::Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, + const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c) : scale_factor_(scale_factor), range_to_const_c_(range_to_const_c), range_to_zero_c_(range_to_zero_c), @@ -25,10 +24,10 @@ SensorBase::SensorBase(const libra::Matrix& scale_factor, const libra:: } template -SensorBase::~SensorBase() {} +Sensor::~Sensor() {} template -libra::Vector SensorBase::Measure(const libra::Vector true_value_c) { +libra::Vector Sensor::Measure(const libra::Vector true_value_c) { libra::Vector calc_value_c; calc_value_c = scale_factor_ * true_value_c; calc_value_c += bias_c_; @@ -41,7 +40,7 @@ libra::Vector SensorBase::Measure(const libra::Vector true_value_c) { } template -libra::Vector SensorBase::Clip(const libra::Vector input_c) { +libra::Vector Sensor::Clip(const libra::Vector input_c) { libra::Vector output_c; for (size_t i = 0; i < N; ++i) { if (input_c[i] >= range_to_const_c_[i] && input_c[i] < range_to_zero_c_[i]) { @@ -58,16 +57,16 @@ libra::Vector SensorBase::Clip(const libra::Vector input_c) { } template -void SensorBase::RangeCheck(void) { +void Sensor::RangeCheck(void) { for (size_t i = 0; i < N; i++) { if (range_to_const_c_[i] < 0.0 || range_to_zero_c_[i] < 0.0) { - std::cout << "SensorBase: Range should be positive!!\n"; + std::cout << "Sensor: Range should be positive!!\n"; std::cout << "The range values are set as positive.\n"; range_to_zero_c_[i] = fabs(range_to_zero_c_[i]); range_to_const_c_[i] = fabs(range_to_const_c_[i]); } if (range_to_const_c_[i] > range_to_zero_c_[i]) { - std::cout << "SensorBase: range_zero should be greater than range_const!!\n"; + std::cout << "Sensor: range_zero should be greater than range_const!!\n"; std::cout << "The range_zero is set as twice value of the range_const.\n"; range_to_zero_c_[i] = 2.0 * range_to_const_c_[i]; } diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 2cf873cad..294e7ad2e 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -201,7 +201,7 @@ class GNSSReceiver : public Component, public ILoggable { void SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::string gnss_id); /** * @fn AddNoise - * @brief Substitutional method for "Measure" in other sensor models inherited SensorBase class + * @brief Substitutional method for "Measure" in other sensor models inherited Sensor class * @param [in] location_true_eci: True position of the spacecraft in the ECI frame [m] * @param [in] location_true_ecef: True position of the spacecraft in the ECEF frame [m] */ diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index c5b10f6d5..f36bdc76c 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,13 +5,13 @@ #include "gyro_sensor.hpp" -Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, +Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_gen), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} -Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, +Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_gen, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} Gyro::~Gyro() {} diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index beab20915..4c5bcac89 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -19,7 +19,7 @@ const size_t kGyroDim = 3; //!< Dimension of gyro sensor * @class Gyro * @brief Class to emulate gyro sensor */ -class Gyro : public Component, public SensorBase, public ILoggable { +class Gyro : public Component, public Sensor, public ILoggable { public: /** * @fn Gyro @@ -31,7 +31,7 @@ class Gyro : public Component, public SensorBase, public ILoggable { * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + Gyro(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics); /** * @fn Gyro @@ -44,7 +44,7 @@ class Gyro : public Component, public SensorBase, public ILoggable { * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, + Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics); /** * @fn ~Gyro diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 9c5eb1025..a7705a5a8 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -19,8 +19,8 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + // Sensor + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); Gyro gyro(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, dynamics); @@ -39,8 +39,8 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + // Sensor + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); // PowerPort power_port->InitializeWithInitializeFile(fname); diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index 64aff1006..f725b4d84 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -19,8 +19,8 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str Quaternion q_b2c; magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); - // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + // Sensor + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); MagSensor magsensor(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, magnet); return magsensor; @@ -39,8 +39,8 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se Quaternion q_b2c; magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); - // SensorBase - SensorBase sensor_base = ReadSensorBaseInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + // Sensor + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); // PowerPort power_port->InitializeWithInitializeFile(fname); diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 3ebe30eda..5d1d5cd24 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -6,12 +6,12 @@ #include -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const Quaternion& q_b2c, +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_gen), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, + : Component(prescaler, clock_gen), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_gen, power_port), SensorBase(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + : Component(prescaler, clock_gen, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 83712dde0..df08eafaf 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -19,7 +19,7 @@ const size_t kMagDim = 3; //!< Dimension of magnetometer * @class MagSensor * @brief Class to emulate magnetometer */ -class MagSensor : public Component, public SensorBase, public ILoggable { +class MagSensor : public Component, public Sensor, public ILoggable { public: /** * @fn MagSensor @@ -31,7 +31,7 @@ class MagSensor : public Component, public SensorBase, public ILoggable * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_gen, SensorBase& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + MagSensor(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const GeomagneticField* magnet); /** * @fn MagSensor @@ -44,7 +44,7 @@ class MagSensor : public Component, public SensorBase, public ILoggable * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, SensorBase& sensor_base, const int sensor_id, + MagSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const GeomagneticField* magnet); /** * @fn ~MagSensor From b8d37d9809befded0d83cd4d6966072330c2fef6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:29:22 +0100 Subject: [PATCH 0744/1086] Fix public function name --- src/components/base/interface_gpio_component.hpp | 4 ++-- .../examples/example_serial_communication_with_obc.cpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 4 ++-- src/components/ports/gpio_port.cpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/interface_gpio_component.hpp b/src/components/base/interface_gpio_component.hpp index 1dde12df7..7ed129e7b 100644 --- a/src/components/base/interface_gpio_component.hpp +++ b/src/components/base/interface_gpio_component.hpp @@ -19,12 +19,12 @@ class IGPIOCompo { virtual ~IGPIOCompo(){}; /** - * @fn GPIOStateChanged + * @fn GpioStateChanged * @brief Pure virtual function called at the GPIO state is changed like interrupt function. * @param[in] port_id: GPIO port ID * @param[in] is_positive_edge: Flag to express positive edge or not */ - virtual void GPIOStateChanged(const int port_id, const bool is_positive_edge) = 0; + virtual void GpioStateChanged(const int port_id, const bool is_positive_edge) = 0; }; #endif // S2E_COMPONENTS_BASE_CLASSES_INTERFACE_GPIO_COMPONENT_HPP_ diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index b4e8287be..ee50e7e24 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -50,6 +50,6 @@ void ExampleSerialCommunicationWithObc::MainRoutine(int count) { SendTelemetry(0); } -void ExampleSerialCommunicationWithObc::GPIOStateChanged(int port_id, bool isPosedge) { +void ExampleSerialCommunicationWithObc::GpioStateChanged(int port_id, bool isPosedge) { printf("interrupted. portid = %d, isPosedge = %d./n", port_id, isPosedge); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 551deb749..1f766b5cb 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -61,10 +61,10 @@ class ExampleSerialCommunicationWithObc : public Component, public ObcCommunicat // Override functions for IGPIOCompo /** - * @fn GPIOStateChanged + * @fn GpioStateChanged * @brief Interrupt function for GPIO */ - void GPIOStateChanged(int port_id, bool isPosedge); + void GpioStateChanged(int port_id, bool isPosedge); private: const static int MAX_MEMORY_LEN = 100; //!< Maximum memory length diff --git a/src/components/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp index e0eded51d..e299f8045 100644 --- a/src/components/ports/gpio_port.cpp +++ b/src/components/ports/gpio_port.cpp @@ -16,7 +16,7 @@ int GPIOPort::DigitalWrite(bool isHigh) { if (hl_state_ != isHigh) { // Call interaction function when detecting the change of the HIGH/LOW state if (component_ != nullptr) { - component_->GPIOStateChanged(kPortId, isHigh); + component_->GpioStateChanged(kPortId, isHigh); } } hl_state_ = isHigh; From 72733b1192641c48985a0c85beb9127e19ba206c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:40:11 +0100 Subject: [PATCH 0745/1086] Add unsigned --- .../base/uart_communication_with_obc.cpp | 11 +++++----- .../base/uart_communication_with_obc.hpp | 22 +++++++++---------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index dac7d3edd..6968d1af1 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -7,7 +7,7 @@ #include -ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { +ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); @@ -19,7 +19,8 @@ ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, OBC* obc) : sils_po InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(int sils_port_id, const int tx_buffer_size, const int rx_buffer_size, OBC* obc) +ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, + OBC* obc) : sils_port_id_(sils_port_id), tx_buffer_size_(tx_buffer_size), rx_buffer_size_(rx_buffer_size), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; @@ -45,8 +46,8 @@ ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, cons InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buffer_size, - const int rx_buffer_size, HilsPortManager* hils_port_manager) +ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), tx_buffer_size_(tx_buffer_size), @@ -130,7 +131,7 @@ void ObcCommunicationBase::InitializeObcComBase() { } } -int ObcCommunicationBase::ReceiveCommand(const int offset, const int rec_size) { +int ObcCommunicationBase::ReceiveCommand(const int offset, const unsigned int rec_size) { if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; if (offset > rx_buffer_size_) return -1; if (offset + rec_size > rx_buffer_size_) return -1; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 41c333c48..c15916027 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -35,7 +35,7 @@ class ObcCommunicationBase { * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode * @param [in] obc: The communication target OBC */ - ObcCommunicationBase(const int sils_port_id, OBC* obc); + ObcCommunicationBase(const unsigned int sils_port_id, OBC* obc); /** * @fn ObcCommunicationBase * @brief Constructor for SILS mode @@ -44,7 +44,7 @@ class ObcCommunicationBase { * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] obc: The communication target OBC */ - ObcCommunicationBase(const int sils_port_id, const int tx_buffer_size, const int rx_buffer_size, OBC* obc); + ObcCommunicationBase(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OBC* obc); /** * @fn ObcCommunicationBase * @brief Constructor for HILS mode @@ -63,8 +63,8 @@ class ObcCommunicationBase { * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] hils_port_manager: HILS port manager */ - ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const int tx_buffer_size, const int rx_buffer_size, - HilsPortManager* hils_port_manager); + ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); /** * @fn ObcCommunicationBase * @brief Constructor for both SILS and HILS mode @@ -89,7 +89,7 @@ class ObcCommunicationBase { inline bool IsConnected() const { return is_connected_; } protected: - int ReceiveCommand(const int offset, const int rec_size); + int ReceiveCommand(const int offset, const unsigned int rec_size); int SendTelemetry(const int offset); std::vector tx_buffer_; std::vector rx_buffer_; @@ -97,12 +97,12 @@ class ObcCommunicationBase { private: const int kDefaultBufferSize = 1024; //!< Default buffer size Fixme: The magic number. This is depending on uart_port.hpp. - int sils_port_id_; //!< Port ID for SILS - int hils_port_id_; //!< Port ID for HILS - int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 - int tx_buffer_size_; //!< TX (Component to OBC) buffer size - int rx_buffer_size_; //!< RX (OBC to Component) buffer size - bool is_connected_ = false; //!< Connection flag + unsigned int sils_port_id_; //!< Port ID for SILS + unsigned int hils_port_id_; //!< Port ID for HILS + unsigned int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 + unsigned int tx_buffer_size_; //!< TX (Component to OBC) buffer size + unsigned int rx_buffer_size_; //!< RX (OBC to Component) buffer size + bool is_connected_ = false; //!< Connection flag OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode From 69bfecd61ebb14a3640f4c1b884b7bba563a43b9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:41:07 +0100 Subject: [PATCH 0746/1086] Rename OBCCommunicationBase to UartCommunicationWithObc --- .../base/uart_communication_with_obc.cpp | 24 +++++++------- .../base/uart_communication_with_obc.hpp | 32 +++++++++---------- .../example_serial_communication_for_hils.cpp | 2 +- .../example_serial_communication_for_hils.hpp | 2 +- .../example_serial_communication_with_obc.cpp | 4 +-- .../example_serial_communication_with_obc.hpp | 2 +- 6 files changed, 33 insertions(+), 33 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index 6968d1af1..27955d7ba 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -7,7 +7,7 @@ #include -ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { +UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); @@ -19,8 +19,8 @@ ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, OBC* InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, - OBC* obc) +UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, OBC* obc) : sils_port_id_(sils_port_id), tx_buffer_size_(tx_buffer_size), rx_buffer_size_(rx_buffer_size), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; @@ -33,7 +33,7 @@ ObcCommunicationBase::ObcCommunicationBase(const unsigned int sils_port_id, cons InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager) +UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::HILS; @@ -46,8 +46,8 @@ ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, cons InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, - const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) +UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), tx_buffer_size_(tx_buffer_size), @@ -64,8 +64,8 @@ ObcCommunicationBase::ObcCommunicationBase(const unsigned int hils_port_id, cons InitializeObcComBase(); } -ObcCommunicationBase::ObcCommunicationBase(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, - HilsPortManager* hils_port_manager) +UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, + HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), baud_rate_(baud_rate), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::HILS; @@ -77,7 +77,7 @@ ObcCommunicationBase::ObcCommunicationBase(const int sils_port_id, OBC* obc, con InitializeObcComBase(); } -ObcCommunicationBase::~ObcCommunicationBase() { +UartCommunicationWithObc::~UartCommunicationWithObc() { if (is_connected_ == false) return; int ret; switch (simulation_mode_) { @@ -102,7 +102,7 @@ ObcCommunicationBase::~ObcCommunicationBase() { } } -void ObcCommunicationBase::InitializeObcComBase() { +void UartCommunicationWithObc::InitializeObcComBase() { int ret; switch (simulation_mode_) { case OBC_COM_UART_MODE::MODE_ERROR: @@ -131,7 +131,7 @@ void ObcCommunicationBase::InitializeObcComBase() { } } -int ObcCommunicationBase::ReceiveCommand(const int offset, const unsigned int rec_size) { +int UartCommunicationWithObc::ReceiveCommand(const int offset, const unsigned int rec_size) { if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; if (offset > rx_buffer_size_) return -1; if (offset + rec_size > rx_buffer_size_) return -1; @@ -153,7 +153,7 @@ int ObcCommunicationBase::ReceiveCommand(const int offset, const unsigned int re ; } } -int ObcCommunicationBase::SendTelemetry(const int offset) { +int UartCommunicationWithObc::SendTelemetry(const int offset) { if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; int tlm_size = GenerateTelemetry(); if (offset > rx_buffer_size_) return -1; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index c15916027..e9a818488 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -22,40 +22,40 @@ enum class OBC_COM_UART_MODE { }; /** - * @class ObcCommunicationBase + * @class UartCommunicationWithObc * @brief Base class for serial communication (e.g., UART) with OBC flight software * @note Components which want to communicate with OBC using serial communication have to inherit this. */ -class ObcCommunicationBase { +class UartCommunicationWithObc { public: /** - * @fn ObcCommunicationBase + * @fn UartCommunicationWithObc * @brief Constructor for SILS mode * @note Default buffer size is used * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode * @param [in] obc: The communication target OBC */ - ObcCommunicationBase(const unsigned int sils_port_id, OBC* obc); + UartCommunicationWithObc(const unsigned int sils_port_id, OBC* obc); /** - * @fn ObcCommunicationBase + * @fn UartCommunicationWithObc * @brief Constructor for SILS mode * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode * @param [in] tx_buffer_size: TX (Component to OBC) buffer size * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] obc: The communication target OBC */ - ObcCommunicationBase(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OBC* obc); + UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OBC* obc); /** - * @fn ObcCommunicationBase + * @fn UartCommunicationWithObc * @brief Constructor for HILS mode * @note Default buffer size is used * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager); + UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager); /** - * @fn ObcCommunicationBase + * @fn UartCommunicationWithObc * @brief Constructor for HILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port @@ -63,10 +63,10 @@ class ObcCommunicationBase { * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] hils_port_manager: HILS port manager */ - ObcCommunicationBase(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, - const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); + UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, + const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); /** - * @fn ObcCommunicationBase + * @fn UartCommunicationWithObc * @brief Constructor for both SILS and HILS mode * @note Default buffer size is used * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode @@ -75,13 +75,13 @@ class ObcCommunicationBase { * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ObcCommunicationBase(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, - HilsPortManager* hils_port_manager); + UartCommunicationWithObc(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, + HilsPortManager* hils_port_manager); /** - * @fn ~ObcCommunicationBase + * @fn ~UartCommunicationWithObc * @brief Destructor */ - ~ObcCommunicationBase(); + ~UartCommunicationWithObc(); /** * @fn IsConnected * @brief Return connection flag diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index 31fbf9810..b6c32f5e4 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -9,7 +9,7 @@ ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id) - : Component(300, clock_gen), ObcCommunicationBase(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} + : Component(300, clock_gen), UartCommunicationWithObc(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} ExampleSerialCommunicationForHils::~ExampleSerialCommunicationForHils() {} diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index d23276817..e19053c70 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -20,7 +20,7 @@ * - the last byte : \0 * The responder mode: ExpHils returns the message as received */ -class ExampleSerialCommunicationForHils : public Component, public ObcCommunicationBase { +class ExampleSerialCommunicationForHils : public Component, public UartCommunicationWithObc { public: /** * @fn ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index ee50e7e24..f232851c3 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -8,11 +8,11 @@ #include ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) - : Component(1000, clock_gen), ObcCommunicationBase(port_id, obc) { + : Component(1000, clock_gen), UartCommunicationWithObc(port_id, obc) { Initialize(); } ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) - : Component(prescaler, clock_gen), ObcCommunicationBase(port_id, obc) { + : Component(prescaler, clock_gen), UartCommunicationWithObc(port_id, obc) { Initialize(); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 1f766b5cb..165a5798e 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -25,7 +25,7 @@ * - The last byte: "\n" * - The telemetry is automatically generated */ -class ExampleSerialCommunicationWithObc : public Component, public ObcCommunicationBase, public IGPIOCompo { +class ExampleSerialCommunicationWithObc : public Component, public UartCommunicationWithObc, public IGPIOCompo { public: /** * @fn ExampleSerialCommunicationWithObc From 888f072dc13c6fb84a2db884006be40113f0886e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:43:03 +0100 Subject: [PATCH 0747/1086] Add const and unsigned --- src/components/ports/gpio_port.cpp | 4 ++-- src/components/ports/gpio_port.hpp | 10 +++++----- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/components/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp index e299f8045..84cd8b641 100644 --- a/src/components/ports/gpio_port.cpp +++ b/src/components/ports/gpio_port.cpp @@ -5,14 +5,14 @@ #include "gpio_port.hpp" -GPIOPort::GPIOPort(int port_id, IGPIOCompo* compo) : kPortId(port_id) { +GPIOPort::GPIOPort(const unsigned int port_id, IGPIOCompo* compo) : kPortId(port_id) { hl_state_ = GPIO_LOW; component_ = compo; } GPIOPort::~GPIOPort() {} -int GPIOPort::DigitalWrite(bool isHigh) { +int GPIOPort::DigitalWrite(const bool isHigh) { if (hl_state_ != isHigh) { // Call interaction function when detecting the change of the HIGH/LOW state if (component_ != nullptr) { diff --git a/src/components/ports/gpio_port.hpp b/src/components/ports/gpio_port.hpp index 8cd0c460f..7573b5f4c 100644 --- a/src/components/ports/gpio_port.hpp +++ b/src/components/ports/gpio_port.hpp @@ -23,7 +23,7 @@ class GPIOPort { * @param [in] port_id_: ID of the GPIO port * @param [in] compo: Component which has the GPIO port */ - GPIOPort(int port_id_, IGPIOCompo* compo = nullptr); + GPIOPort(const unsigned int port_id_, IGPIOCompo* compo = nullptr); /** * @fn ~GPIOPort * @brief Destructor @@ -36,7 +36,7 @@ class GPIOPort { * @param [in] isHigh: Use GPIO_HIGH or GPIO_LOW * @return always zero */ - int DigitalWrite(bool isHigh); + int DigitalWrite(const bool isHigh); /** * @fn DigitalRead @@ -46,9 +46,9 @@ class GPIOPort { bool DigitalRead(); private: - const int kPortId; //!< Port ID - IGPIOCompo* component_; //!< Component which has the GPIO port - bool hl_state_; //!< GPIO High/Low state + const unsigned int kPortId; //!< Port ID + IGPIOCompo* component_; //!< Component which has the GPIO port + bool hl_state_; //!< GPIO High/Low state }; #endif // S2E_COMPONENTS_PORTS_GPIO_PORT_HPP_ From a29f446587a4635168257956c4d3a5dad320e7e6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:43:47 +0100 Subject: [PATCH 0748/1086] Fix private variables --- src/components/ports/gpio_port.cpp | 8 ++++---- src/components/ports/gpio_port.hpp | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/components/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp index 84cd8b641..5f965bc0a 100644 --- a/src/components/ports/gpio_port.cpp +++ b/src/components/ports/gpio_port.cpp @@ -6,21 +6,21 @@ #include "gpio_port.hpp" GPIOPort::GPIOPort(const unsigned int port_id, IGPIOCompo* compo) : kPortId(port_id) { - hl_state_ = GPIO_LOW; + high_low_state_ = GPIO_LOW; component_ = compo; } GPIOPort::~GPIOPort() {} int GPIOPort::DigitalWrite(const bool isHigh) { - if (hl_state_ != isHigh) { + if (high_low_state_ != isHigh) { // Call interaction function when detecting the change of the HIGH/LOW state if (component_ != nullptr) { component_->GpioStateChanged(kPortId, isHigh); } } - hl_state_ = isHigh; + high_low_state_ = isHigh; return 0; } -bool GPIOPort::DigitalRead() { return hl_state_; } +bool GPIOPort::DigitalRead() { return high_low_state_; } diff --git a/src/components/ports/gpio_port.hpp b/src/components/ports/gpio_port.hpp index 7573b5f4c..a59e95e4a 100644 --- a/src/components/ports/gpio_port.hpp +++ b/src/components/ports/gpio_port.hpp @@ -48,7 +48,7 @@ class GPIOPort { private: const unsigned int kPortId; //!< Port ID IGPIOCompo* component_; //!< Component which has the GPIO port - bool hl_state_; //!< GPIO High/Low state + bool high_low_state_; //!< GPIO High/Low state }; #endif // S2E_COMPONENTS_PORTS_GPIO_PORT_HPP_ From 72a133fdae68f7d544e9c10f6b0f856efc02226a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:45:21 +0100 Subject: [PATCH 0749/1086] Fix function argument name --- src/components/ports/gpio_port.cpp | 12 ++++++------ src/components/ports/gpio_port.hpp | 8 ++++---- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp index 5f965bc0a..75ddc02c7 100644 --- a/src/components/ports/gpio_port.cpp +++ b/src/components/ports/gpio_port.cpp @@ -5,21 +5,21 @@ #include "gpio_port.hpp" -GPIOPort::GPIOPort(const unsigned int port_id, IGPIOCompo* compo) : kPortId(port_id) { +GPIOPort::GPIOPort(const unsigned int port_id, IGPIOCompo* component) : kPortId(port_id) { high_low_state_ = GPIO_LOW; - component_ = compo; + component_ = component; } GPIOPort::~GPIOPort() {} -int GPIOPort::DigitalWrite(const bool isHigh) { - if (high_low_state_ != isHigh) { +int GPIOPort::DigitalWrite(const bool is_high) { + if (high_low_state_ != is_high) { // Call interaction function when detecting the change of the HIGH/LOW state if (component_ != nullptr) { - component_->GpioStateChanged(kPortId, isHigh); + component_->GpioStateChanged(kPortId, is_high); } } - high_low_state_ = isHigh; + high_low_state_ = is_high; return 0; } diff --git a/src/components/ports/gpio_port.hpp b/src/components/ports/gpio_port.hpp index a59e95e4a..8eec58b93 100644 --- a/src/components/ports/gpio_port.hpp +++ b/src/components/ports/gpio_port.hpp @@ -21,9 +21,9 @@ class GPIOPort { * @fn GPIOPort * @brief Constructor * @param [in] port_id_: ID of the GPIO port - * @param [in] compo: Component which has the GPIO port + * @param [in] component: Component which has the GPIO port */ - GPIOPort(const unsigned int port_id_, IGPIOCompo* compo = nullptr); + GPIOPort(const unsigned int port_id_, IGPIOCompo* component = nullptr); /** * @fn ~GPIOPort * @brief Destructor @@ -33,10 +33,10 @@ class GPIOPort { /** * @fn DigitalWrite * @brief Change the GPIO state - * @param [in] isHigh: Use GPIO_HIGH or GPIO_LOW + * @param [in] is_high: Use GPIO_HIGH or GPIO_LOW * @return always zero */ - int DigitalWrite(const bool isHigh); + int DigitalWrite(const bool is_high); /** * @fn DigitalRead From 491289114b089000a77a807783b7e29c0dab5c95 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:46:57 +0100 Subject: [PATCH 0750/1086] Add unsigned --- src/components/base/uart_communication_with_obc.cpp | 4 ++-- src/components/base/uart_communication_with_obc.hpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index 27955d7ba..ffbdafd4c 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -131,7 +131,7 @@ void UartCommunicationWithObc::InitializeObcComBase() { } } -int UartCommunicationWithObc::ReceiveCommand(const int offset, const unsigned int rec_size) { +int UartCommunicationWithObc::ReceiveCommand(const unsigned int offset, const unsigned int rec_size) { if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; if (offset > rx_buffer_size_) return -1; if (offset + rec_size > rx_buffer_size_) return -1; @@ -153,7 +153,7 @@ int UartCommunicationWithObc::ReceiveCommand(const int offset, const unsigned in ; } } -int UartCommunicationWithObc::SendTelemetry(const int offset) { +int UartCommunicationWithObc::SendTelemetry(const unsigned int offset) { if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; int tlm_size = GenerateTelemetry(); if (offset > rx_buffer_size_) return -1; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index e9a818488..dd5521757 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -89,13 +89,13 @@ class UartCommunicationWithObc { inline bool IsConnected() const { return is_connected_; } protected: - int ReceiveCommand(const int offset, const unsigned int rec_size); - int SendTelemetry(const int offset); + int ReceiveCommand(const unsigned int offset, const unsigned int rec_size); + int SendTelemetry(const unsigned int offset); std::vector tx_buffer_; std::vector rx_buffer_; private: - const int kDefaultBufferSize = 1024; //!< Default buffer size Fixme: The magic number. This is depending on uart_port.hpp. + const unsigned int kDefaultBufferSize = 1024; //!< Default buffer size Fixme: The magic number. This is depending on uart_port.hpp. unsigned int sils_port_id_; //!< Port ID for SILS unsigned int hils_port_id_; //!< Port ID for HILS From 90a52d248505484063b6089fea8d476459e1e8a6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:48:18 +0100 Subject: [PATCH 0751/1086] Fix private variable name --- src/components/ports/hils_i2c_target_port.cpp | 6 +++--- src/components/ports/hils_i2c_target_port.hpp | 2 +- src/components/ports/i2c_port.cpp | 6 +++--- src/components/ports/i2c_port.hpp | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/ports/hils_i2c_target_port.cpp b/src/components/ports/hils_i2c_target_port.cpp index 52f8ba868..d28f5b58f 100644 --- a/src/components/ports/hils_i2c_target_port.cpp +++ b/src/components/ports/hils_i2c_target_port.cpp @@ -21,7 +21,7 @@ void HilsI2cTargetPort::RegisterDevice() { device_registers_[i] = 0x00; } for (unsigned char i = 0; i < kDefaultCmdSize; i++) { - cmd_buffer_[i] = 0x00; + command_buffer_[i] = 0x00; } } @@ -50,7 +50,7 @@ int HilsI2cTargetPort::ReadCommand(unsigned char* rx_data, const unsigned int le return -1; } for (unsigned char i = 0; i < length; i++) { - rx_data[i] = cmd_buffer_[i]; + rx_data[i] = command_buffer_[i]; } return length; } @@ -68,7 +68,7 @@ int HilsI2cTargetPort::Receive() // from I2C-USB Target converter printf("\n"); #endif for (unsigned char i = 0; i < received_bytes; i++) { - cmd_buffer_[i] = rx_buf[i]; + command_buffer_[i] = rx_buf[i]; } if (received_bytes == 1) // length == 1 means setting of read register address diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index 7148c0b7b..d99f3868b 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -104,7 +104,7 @@ class HilsI2cTargetPort : public HilsUartPort { std::map device_registers_; /** @brief Buffer for the command from COM port : **/ - std::map cmd_buffer_; + std::map command_buffer_; }; #endif // S2E_COMPONENTS_PORTS_HILS_I2C_TARGET_PORT_HPP_ diff --git a/src/components/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp index 7a753e7ad..b6a45faaa 100644 --- a/src/components/ports/i2c_port.cpp +++ b/src/components/ports/i2c_port.cpp @@ -16,7 +16,7 @@ void I2CPort::RegisterDevice(const unsigned char i2c_addr) { device_registers_[std::make_pair(i2c_addr, i)] = 0x00; } for (unsigned char i = 0; i < kDefaultCmdBufferSize; i++) { - cmd_buffer_[std::make_pair(i2c_addr, i)] = 0x00; + command_buffer_[std::make_pair(i2c_addr, i)] = 0x00; } } @@ -69,7 +69,7 @@ unsigned char I2CPort::WriteCommand(const unsigned char i2c_addr, const unsigned return 0; } for (unsigned char i = 0; i < length; i++) { - cmd_buffer_[std::make_pair(i2c_addr, i)] = tx_data[i]; + command_buffer_[std::make_pair(i2c_addr, i)] = tx_data[i]; } if (length == 1) // length == 1 means setting of read register address @@ -89,7 +89,7 @@ unsigned char I2CPort::ReadCommand(const unsigned char i2c_addr, unsigned char* return 0; } for (unsigned char i = 0; i < length; i++) { - rx_data[i] = cmd_buffer_[std::make_pair(i2c_addr, i)]; + rx_data[i] = command_buffer_[std::make_pair(i2c_addr, i)]; } return length; } diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 7af29dcf6..036d30ef6 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -106,7 +106,7 @@ class I2CPort { std::map, unsigned char> device_registers_; /** @brief Buffer for the command from OBC : **/ - std::map, unsigned char> cmd_buffer_; + std::map, unsigned char> command_buffer_; }; #endif // S2E_COMPONENTS_PORTS_I2C_PORT_HPP_ From e01ab177487bd3511efdd575c9bd958a73b468f3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:48:53 +0100 Subject: [PATCH 0752/1086] Fix private variable name --- src/components/ports/hils_i2c_target_port.cpp | 10 +++++----- src/components/ports/hils_i2c_target_port.hpp | 6 +++--- src/components/ports/i2c_port.cpp | 16 ++++++++-------- src/components/ports/i2c_port.hpp | 4 ++-- 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/components/ports/hils_i2c_target_port.cpp b/src/components/ports/hils_i2c_target_port.cpp index d28f5b58f..f7f651d5f 100644 --- a/src/components/ports/hils_i2c_target_port.cpp +++ b/src/components/ports/hils_i2c_target_port.cpp @@ -27,20 +27,20 @@ void HilsI2cTargetPort::RegisterDevice() { int HilsI2cTargetPort::WriteRegister(const unsigned char reg_addr) { if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; return 0; // FIXME: return should be 1 when success } int HilsI2cTargetPort::WriteRegister(const unsigned char reg_addr, const unsigned char value) { if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; device_registers_[reg_addr] = value; return 0; // FIXME: return should be 1 when success } unsigned char HilsI2cTargetPort::ReadRegister(const unsigned char reg_addr) { if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; unsigned char ret = device_registers_[reg_addr]; return ret; } @@ -88,10 +88,10 @@ int HilsI2cTargetPort::Receive() // from I2C-USB Target converter int HilsI2cTargetPort::Send(const unsigned char len) // to I2C-USB Target Converter { - if (saved_reg_addr_ + len > max_register_number_) return -1; + if (saved_register_address_ + len > max_register_number_) return -1; unsigned char tx_buf[kDefaultTxSize] = {0}; for (unsigned char i = 0; i < len; i++) { - tx_buf[i] = device_registers_[saved_reg_addr_ + i]; + tx_buf[i] = device_registers_[saved_register_address_ + i]; } #ifdef HILS_I2C_TARGET_PORT_SHOW_DEBUG_DATA for (int i = 0; i < len; i++) { diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index d99f3868b..787eb9605 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -96,9 +96,9 @@ class HilsI2cTargetPort : public HilsUartPort { int GetStoredFrameCounter(); private: - unsigned char max_register_number_ = 0xff; //!< Maximum register number - unsigned char saved_reg_addr_ = 0x00; //!< Saved register address - unsigned int stored_frame_counter_ = 0; //!< Send a few frames of telemetry to the converter in advance. + unsigned char max_register_number_ = 0xff; //!< Maximum register number + unsigned char saved_register_address_ = 0x00; //!< Saved register address + unsigned int stored_frame_counter_ = 0; //!< Send a few frames of telemetry to the converter in advance. /** @brief Device register: < register address, value> **/ std::map device_registers_; diff --git a/src/components/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp index b6a45faaa..2e17ee345 100644 --- a/src/components/ports/i2c_port.cpp +++ b/src/components/ports/i2c_port.cpp @@ -24,13 +24,13 @@ int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg UNUSED(i2c_addr); // TODO: consider this argument is really needed. if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; return 1; } int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char value) { if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; device_registers_[std::make_pair(i2c_addr, reg_addr)] = value; return 1; } @@ -40,7 +40,7 @@ int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr, float value) { if(reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; + saved_register_address_ = reg_addr; unsigned char* value_ptr = reinterpret_cast(&value); for(size_t i = 0; i < sizeof(float); i++) { @@ -51,16 +51,16 @@ reg_addr, float value) */ unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr) { - unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_reg_addr_)]; - saved_reg_addr_++; - if (saved_reg_addr_ >= max_register_number_) saved_reg_addr_ = 0; + unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; + saved_register_address_++; + if (saved_register_address_ >= max_register_number_) saved_register_address_ = 0; return ret; } unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr, const unsigned char reg_addr) { if (reg_addr >= max_register_number_) return 0; - saved_reg_addr_ = reg_addr; - unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_reg_addr_)]; + saved_register_address_ = reg_addr; + unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; return ret; } diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 036d30ef6..54983474e 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -99,8 +99,8 @@ class I2CPort { unsigned char ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length); private: - unsigned char max_register_number_ = 0xff; //!< Maximum register number - unsigned char saved_reg_addr_ = 0x00; //!< Saved register address + unsigned char max_register_number_ = 0xff; //!< Maximum register number + unsigned char saved_register_address_ = 0x00; //!< Saved register address /** @brief Device register: **/ std::map, unsigned char> device_registers_; From a69f45fc2bc31dbcd8a3006b8c5b9272c34f7255 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:50:45 +0100 Subject: [PATCH 0753/1086] Fix function argument variables --- src/components/ports/hils_i2c_target_port.cpp | 32 +++++++++---------- src/components/ports/hils_i2c_target_port.hpp | 16 +++++----- src/components/ports/i2c_port.cpp | 28 ++++++++-------- src/components/ports/i2c_port.hpp | 16 +++++----- 4 files changed, 46 insertions(+), 46 deletions(-) diff --git a/src/components/ports/hils_i2c_target_port.cpp b/src/components/ports/hils_i2c_target_port.cpp index f7f651d5f..73d7e38a4 100644 --- a/src/components/ports/hils_i2c_target_port.cpp +++ b/src/components/ports/hils_i2c_target_port.cpp @@ -25,23 +25,23 @@ void HilsI2cTargetPort::RegisterDevice() { } } -int HilsI2cTargetPort::WriteRegister(const unsigned char reg_addr) { - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; +int HilsI2cTargetPort::WriteRegister(const unsigned char register_address) { + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; return 0; // FIXME: return should be 1 when success } -int HilsI2cTargetPort::WriteRegister(const unsigned char reg_addr, const unsigned char value) { - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; - device_registers_[reg_addr] = value; +int HilsI2cTargetPort::WriteRegister(const unsigned char register_address, const unsigned char value) { + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; + device_registers_[register_address] = value; return 0; // FIXME: return should be 1 when success } -unsigned char HilsI2cTargetPort::ReadRegister(const unsigned char reg_addr) { - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; - unsigned char ret = device_registers_[reg_addr]; +unsigned char HilsI2cTargetPort::ReadRegister(const unsigned char register_address) { + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; + unsigned char ret = device_registers_[register_address]; return ret; } @@ -86,20 +86,20 @@ int HilsI2cTargetPort::Receive() // from I2C-USB Target converter return received_bytes; } -int HilsI2cTargetPort::Send(const unsigned char len) // to I2C-USB Target Converter +int HilsI2cTargetPort::Send(const unsigned char data_length) // to I2C-USB Target Converter { - if (saved_register_address_ + len > max_register_number_) return -1; + if (saved_register_address_ + data_length > max_register_number_) return -1; unsigned char tx_buf[kDefaultTxSize] = {0}; - for (unsigned char i = 0; i < len; i++) { + for (unsigned char i = 0; i < data_length; i++) { tx_buf[i] = device_registers_[saved_register_address_ + i]; } #ifdef HILS_I2C_TARGET_PORT_SHOW_DEBUG_DATA - for (int i = 0; i < len; i++) { + for (int i = 0; i < data_length; i++) { printf("%02x ", tx_buf[i]); } printf("\n"); #endif - int ret = WriteTx(tx_buf, 0, len); + int ret = WriteTx(tx_buf, 0, data_length); stored_frame_counter_++; return ret; } diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index 787eb9605..83e79c2fa 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -49,24 +49,24 @@ class HilsI2cTargetPort : public HilsUartPort { /** * @fn WriteRegister * @brief Set the register address to write a value in the next step - * @param [in] reg_addr: Register address to write a value in the next step + * @param [in] register_address: Register address to write a value in the next step */ - int WriteRegister(const unsigned char reg_addr); + int WriteRegister(const unsigned char register_address); /** * @fn WriteRegister * @brief Write a value in the register of this device - * @param [in] reg_addr: Register address of this device + * @param [in] register_address: Register address of this device * @param [in] value: 1 Byte value */ - int WriteRegister(const unsigned char reg_addr, const unsigned char value); + int WriteRegister(const unsigned char register_address, const unsigned char value); /** * @fn ReadRegister * @brief Read the register value of the target device. The register address is used as the previous accessed address - * @param [in] reg_addr: Register address of the target device + * @param [in] register_address: Register address of the target device * @return Read data */ - unsigned char ReadRegister(const unsigned char reg_addr); + unsigned char ReadRegister(const unsigned char register_address); /** * @fn ReadCommand * @brief Read command requested from the COM port to the component @@ -85,10 +85,10 @@ class HilsI2cTargetPort : public HilsUartPort { /** * @fn Send * @brief Send data in the register to the I2C-USB converter. - * @param [in] len: Length of the data + * @param [in] data_length: Length of the data * @return -1: an error happened, others: length of sent data */ - int Send(const unsigned char len); + int Send(const unsigned char data_length); /** * @fn GetStoredFrameCounter * @brief Receive stored frame counter diff --git a/src/components/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp index 2e17ee345..05bec10f0 100644 --- a/src/components/ports/i2c_port.cpp +++ b/src/components/ports/i2c_port.cpp @@ -20,31 +20,31 @@ void I2CPort::RegisterDevice(const unsigned char i2c_addr) { } } -int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr) { +int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address) { UNUSED(i2c_addr); // TODO: consider this argument is really needed. - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; return 1; } -int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char value) { - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; - device_registers_[std::make_pair(i2c_addr, reg_addr)] = value; +int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value) { + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; + device_registers_[std::make_pair(i2c_addr, register_address)] = value; return 1; } /* int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char -reg_addr, float value) +register_address, float value) { - if(reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; + if(register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; unsigned char* value_ptr = reinterpret_cast(&value); for(size_t i = 0; i < sizeof(float); i++) { - WriteRegister(i2c_addr,reg_addr, value_ptr[i]); + WriteRegister(i2c_addr,register_address, value_ptr[i]); } return 1; } @@ -57,9 +57,9 @@ unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr) { return ret; } -unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr, const unsigned char reg_addr) { - if (reg_addr >= max_register_number_) return 0; - saved_register_address_ = reg_addr; +unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr, const unsigned char register_address) { + if (register_address >= max_register_number_) return 0; + saved_register_address_ = register_address; unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; return ret; } diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 54983474e..8c27e1dca 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -40,27 +40,27 @@ class I2CPort { * @fn WriteRegister * @brief Set the register address to write a value in the next step * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address to write a value in the next step + * @param [in] register_address: Register address to write a value in the next step * @return Return zero when an error is happened. */ - int WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr); + int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address); /** * @fn WriteRegister * @brief Write a value in the target device's register * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [in] value: 1 Byte value * @return Return zero when an error is happened. */ - int WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char value); + int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value); /** * @fn WriteRegister * @brief Write a value in the target device's register * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [in] value: float value */ - // int WriteRegister(const unsigned char i2c_addr, const unsigned char reg_addr, float value); // TODO Check this works well + // int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, float value); // TODO Check this works well /** * @fn ReadRegister @@ -73,10 +73,10 @@ class I2CPort { * @fn ReadRegister * @brief Read the register value of the target device. * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] register_address: Register address of the target device * @return Read data */ - unsigned char ReadRegister(const unsigned char i2c_addr, const unsigned char reg_addr); + unsigned char ReadRegister(const unsigned char i2c_addr, const unsigned char register_address); // OBC->Component Command emulation /** From bc0c8a026c2b2a8f7a4ab5154770b5643d295bda Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:51:55 +0100 Subject: [PATCH 0754/1086] Move public const value to private --- src/components/ports/hils_i2c_target_port.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index 83e79c2fa..ca34f1ee0 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -10,9 +10,6 @@ #include "hils_uart_port.hpp" -const int kDefaultCmdSize = 0xff; //!< Default command size -const int kDefaultTxSize = 0xff; //!< Default TX size - /** * @class HilsI2cTargetPort * @brief Class to control I2C-USB converter for the target(device) side from COM port @@ -96,6 +93,8 @@ class HilsI2cTargetPort : public HilsUartPort { int GetStoredFrameCounter(); private: + const unsigned int kDefaultCmdSize = 0xff; //!< Default command size + const unsigned int kDefaultTxSize = 0xff; //!< Default TX size unsigned char max_register_number_ = 0xff; //!< Maximum register number unsigned char saved_register_address_ = 0x00; //!< Saved register address unsigned int stored_frame_counter_ = 0; //!< Send a few frames of telemetry to the converter in advance. From eedb75ea93a5808cf6e8989dac67bbeaf6a53aa7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:53:49 +0100 Subject: [PATCH 0755/1086] Fix private variable name --- src/components/ports/hils_uart_port.cpp | 12 ++++++------ src/components/ports/hils_uart_port.hpp | 4 ++-- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/ports/hils_uart_port.cpp b/src/components/ports/hils_uart_port.cpp index 2d6ff4d1d..e3283a465 100644 --- a/src/components/ports/hils_uart_port.cpp +++ b/src/components/ports/hils_uart_port.cpp @@ -14,8 +14,8 @@ HilsUartPort::HilsUartPort(const unsigned int port_id, const unsigned int baud_r const unsigned int rx_buffer_size) : kPortName(PortName(port_id)), baud_rate_(baud_rate), kTxBufferSize(tx_buffer_size), kRxBufferSize(rx_buffer_size) { // Allocate managed arrays. - tx_buf_ = gcnew bytearray(kTxBufferSize); - rx_buf_ = gcnew bytearray(kRxBufferSize); + tx_buffer_ = gcnew bytearray(kTxBufferSize); + rx_buffer_ = gcnew bytearray(kRxBufferSize); Initialize(); } @@ -109,10 +109,10 @@ int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int count) { unsigned char* buffer_tmp = new unsigned char[count]; memcpy(buffer_tmp, buffer + offset, count); // const unsigned char* -> unsigned char* // Marshal::Copy : Copies data from an unmanaged memory pointer to a managed array. - System::Runtime::InteropServices::Marshal::Copy((System::IntPtr)(buffer_tmp), tx_buf_, 0, count); // unsigned char* -> System::IntPtr + System::Runtime::InteropServices::Marshal::Copy((System::IntPtr)(buffer_tmp), tx_buffer_, 0, count); // unsigned char* -> System::IntPtr delete[] buffer_tmp; try { - port_->Write(tx_buf_, 0, count); + port_->Write(tx_buffer_, 0, count); } catch (System::Exception ^ e) { #ifdef HILS_UART_PORT_SHOW_DEBUG_DATA System::Console::Write(e->Message); @@ -125,9 +125,9 @@ int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int count) { int HilsUartPort::ReadRx(unsigned char* buffer, int offset, int count) { try { - int received_bytes = port_->Read(rx_buf_, 0, count); + int received_bytes = port_->Read(rx_buffer_, 0, count); // Marshal::Copy : Copies data from a managed array to an unmanaged memory pointer. - System::Runtime::InteropServices::Marshal::Copy(rx_buf_, 0, (System::IntPtr)(buffer + offset), count); + System::Runtime::InteropServices::Marshal::Copy(rx_buffer_, 0, (System::IntPtr)(buffer + offset), count); return received_bytes; // TODO: Add enum for exception } catch (System::TimeoutException ^ e) { diff --git a/src/components/ports/hils_uart_port.hpp b/src/components/ports/hils_uart_port.hpp index 2dd520fcf..76580a5ad 100644 --- a/src/components/ports/hils_uart_port.hpp +++ b/src/components/ports/hils_uart_port.hpp @@ -84,8 +84,8 @@ class HilsUartPort { // gcroot is the type-safe wrapper template to refer to a CLR object from the c++ heap reference: // https://docs.microsoft.com/en-us/cpp/dotnet/how-to-declare-handles-in-native-types?view=msvc-160 msclr::gcroot port_; //!< Port - msclr::gcroot tx_buf_; //!< TX Buffer - msclr::gcroot rx_buf_; //!< RX Buffer + msclr::gcroot tx_buffer_; //!< TX Buffer + msclr::gcroot rx_buffer_; //!< RX Buffer /** * @fn PortName From d963be69e543c1f2fb4776d3fa7f76b7042c3b88 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:54:42 +0100 Subject: [PATCH 0756/1086] Fix function argument variables --- src/components/ports/hils_uart_port.cpp | 16 ++++++++-------- src/components/ports/hils_uart_port.hpp | 8 ++++---- src/components/ports/uart_port.cpp | 8 ++++---- src/components/ports/uart_port.hpp | 16 ++++++++-------- 4 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/components/ports/hils_uart_port.cpp b/src/components/ports/hils_uart_port.cpp index e3283a465..0052a8bb5 100644 --- a/src/components/ports/hils_uart_port.cpp +++ b/src/components/ports/hils_uart_port.cpp @@ -105,14 +105,14 @@ int HilsUartPort::OpenPort() { return 0; // Success !! } -int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int count) { - unsigned char* buffer_tmp = new unsigned char[count]; - memcpy(buffer_tmp, buffer + offset, count); // const unsigned char* -> unsigned char* +int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int data_length) { + unsigned char* buffer_tmp = new unsigned char[data_length]; + memcpy(buffer_tmp, buffer + offset, data_length); // const unsigned char* -> unsigned char* // Marshal::Copy : Copies data from an unmanaged memory pointer to a managed array. - System::Runtime::InteropServices::Marshal::Copy((System::IntPtr)(buffer_tmp), tx_buffer_, 0, count); // unsigned char* -> System::IntPtr + System::Runtime::InteropServices::Marshal::Copy((System::IntPtr)(buffer_tmp), tx_buffer_, 0, data_length); // unsigned char* -> System::IntPtr delete[] buffer_tmp; try { - port_->Write(tx_buffer_, 0, count); + port_->Write(tx_buffer_, 0, data_length); } catch (System::Exception ^ e) { #ifdef HILS_UART_PORT_SHOW_DEBUG_DATA System::Console::Write(e->Message); @@ -123,11 +123,11 @@ int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int count) { return 0; } -int HilsUartPort::ReadRx(unsigned char* buffer, int offset, int count) { +int HilsUartPort::ReadRx(unsigned char* buffer, int offset, int data_length) { try { - int received_bytes = port_->Read(rx_buffer_, 0, count); + int received_bytes = port_->Read(rx_buffer_, 0, data_length); // Marshal::Copy : Copies data from a managed array to an unmanaged memory pointer. - System::Runtime::InteropServices::Marshal::Copy(rx_buffer_, 0, (System::IntPtr)(buffer + offset), count); + System::Runtime::InteropServices::Marshal::Copy(rx_buffer_, 0, (System::IntPtr)(buffer + offset), data_length); return received_bytes; // TODO: Add enum for exception } catch (System::TimeoutException ^ e) { diff --git a/src/components/ports/hils_uart_port.hpp b/src/components/ports/hils_uart_port.hpp index 76580a5ad..297f8419e 100644 --- a/src/components/ports/hils_uart_port.hpp +++ b/src/components/ports/hils_uart_port.hpp @@ -55,19 +55,19 @@ class HilsUartPort { * @brief Send data to COM port * @param [in] buffer: Data buffer to send * @param [in] offset: Start offset for the data buffer to send - * @param [in] count: Length of data to send + * @param [in] data_length: Length of data to send * @return 0: success, -1: error */ - int WriteTx(const unsigned char* buffer, int offset, int count); + int WriteTx(const unsigned char* buffer, int offset, int data_length); /** * @fn ReadRx * @brief Read data from COM port * @param [out] buffer: Data buffer to store read data * @param [in] offset: Start offset for the data buffer to read - * @param [in] count: Length of data to read + * @param [in] data_length: Length of data to read * @return received data length: success, negative value: error */ - int ReadRx(unsigned char* buffer, int offset, int count); + int ReadRx(unsigned char* buffer, int offset, int data_length); /** * @fn GetBytesToRead * @brief Get length of byte to read diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index c1bee3a5c..25c670caf 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -19,10 +19,10 @@ SCIPort::~SCIPort() { delete txb_; } -int SCIPort::WriteTx(unsigned char* buffer, int offset, int count) { return txb_->Write(buffer, offset, count); } +int SCIPort::WriteTx(unsigned char* buffer, int offset, int data_length) { return txb_->Write(buffer, offset, data_length); } -int SCIPort::WriteRx(unsigned char* buffer, int offset, int count) { return rxb_->Write(buffer, offset, count); } +int SCIPort::WriteRx(unsigned char* buffer, int offset, int data_length) { return rxb_->Write(buffer, offset, data_length); } -int SCIPort::ReadTx(unsigned char* buffer, int offset, int count) { return txb_->Read(buffer, offset, count); } +int SCIPort::ReadTx(unsigned char* buffer, int offset, int data_length) { return txb_->Read(buffer, offset, data_length); } -int SCIPort::ReadRx(unsigned char* buffer, int offset, int count) { return rxb_->Read(buffer, offset, count); } \ No newline at end of file +int SCIPort::ReadRx(unsigned char* buffer, int offset, int data_length) { return rxb_->Read(buffer, offset, data_length); } \ No newline at end of file diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 59a47a8b2..8b5883704 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -39,38 +39,38 @@ class SCIPort { * @brief Write data to the TX buffer from OBC to Component * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) - * @param [in] count: Length of the data to write + * @param [in] data_length: Length of the data to write * @return Number of written byte */ - int WriteTx(unsigned char* buffer, int offset, int count); + int WriteTx(unsigned char* buffer, int offset, int data_length); /** * @fn WriteRx * @brief Write data to the RX buffer from Component to OBC * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) - * @param [in] count: Length of the data to write + * @param [in] data_length: Length of the data to write * @return Number of written byte */ - int WriteRx(unsigned char* buffer, int offset, int count); + int WriteRx(unsigned char* buffer, int offset, int data_length); /** * @fn ReadTx * @brief Read data from the TX buffer by Component * @param [out] buffer: Data buffer to stored the read data * @param [in] offset: Start offset of the buffer to read (usually zero) - * @param [in] count: Length of the data to read + * @param [in] data_length: Length of the data to read * @return Number of read byte */ - int ReadTx(unsigned char* buffer, int offset, int count); + int ReadTx(unsigned char* buffer, int offset, int data_length); /** * @fn ReadRx * @brief Read data from the TX buffer by OBC * @param [out] buffer: Data buffer to stored the read data * @param [in] offset: Start offset of the buffer to read (usually zero) - * @param [in] count: Length of the data to read + * @param [in] data_length: Length of the data to read * @return Number of read byte */ - int ReadRx(unsigned char* buffer, int offset, int count); + int ReadRx(unsigned char* buffer, int offset, int data_length); private: const static int kDefaultBufferSize = 1024; //!< Default buffer size From 92b9ba2eb4a090f70e454d48341e4d8330d06df7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 10:58:50 +0100 Subject: [PATCH 0757/1086] Add const and unsigned --- src/components/ports/hils_uart_port.cpp | 6 +++--- src/components/ports/hils_uart_port.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/ports/hils_uart_port.cpp b/src/components/ports/hils_uart_port.cpp index 0052a8bb5..ef22549e7 100644 --- a/src/components/ports/hils_uart_port.cpp +++ b/src/components/ports/hils_uart_port.cpp @@ -25,7 +25,7 @@ HilsUartPort::~HilsUartPort() { } // Static method to convert from com port number to com port name. -std::string HilsUartPort::PortName(unsigned int port_id) { return "COM" + std::to_string(port_id); } +std::string HilsUartPort::PortName(const unsigned int port_id) { return "COM" + std::to_string(port_id); } int HilsUartPort::Initialize() { try { @@ -105,7 +105,7 @@ int HilsUartPort::OpenPort() { return 0; // Success !! } -int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int data_length) { +int HilsUartPort::WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { unsigned char* buffer_tmp = new unsigned char[data_length]; memcpy(buffer_tmp, buffer + offset, data_length); // const unsigned char* -> unsigned char* // Marshal::Copy : Copies data from an unmanaged memory pointer to a managed array. @@ -123,7 +123,7 @@ int HilsUartPort::WriteTx(const unsigned char* buffer, int offset, int data_leng return 0; } -int HilsUartPort::ReadRx(unsigned char* buffer, int offset, int data_length) { +int HilsUartPort::ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { try { int received_bytes = port_->Read(rx_buffer_, 0, data_length); // Marshal::Copy : Copies data from a managed array to an unmanaged memory pointer. diff --git a/src/components/ports/hils_uart_port.hpp b/src/components/ports/hils_uart_port.hpp index 297f8419e..d3e45ba3a 100644 --- a/src/components/ports/hils_uart_port.hpp +++ b/src/components/ports/hils_uart_port.hpp @@ -58,7 +58,7 @@ class HilsUartPort { * @param [in] data_length: Length of data to send * @return 0: success, -1: error */ - int WriteTx(const unsigned char* buffer, int offset, int data_length); + int WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn ReadRx * @brief Read data from COM port @@ -67,7 +67,7 @@ class HilsUartPort { * @param [in] data_length: Length of data to read * @return received data length: success, negative value: error */ - int ReadRx(unsigned char* buffer, int offset, int data_length); + int ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn GetBytesToRead * @brief Get length of byte to read @@ -93,7 +93,7 @@ class HilsUartPort { * @param [in] port_id: Port ID like 4 * @return Port name like "COM4" */ - static std::string PortName(unsigned int port_id); + static std::string PortName(const unsigned int port_id); /** * @fn Initialize * @brief Open and initialize the COM port From 1b926c23613fdd3679456d812dd22b7f9413f9e6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:10:54 +0100 Subject: [PATCH 0758/1086] Fix private function name --- src/components/ports/hils_uart_port.cpp | 4 ++-- src/components/ports/hils_uart_port.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/ports/hils_uart_port.cpp b/src/components/ports/hils_uart_port.cpp index ef22549e7..be3d1e16c 100644 --- a/src/components/ports/hils_uart_port.cpp +++ b/src/components/ports/hils_uart_port.cpp @@ -12,7 +12,7 @@ HilsUartPort::HilsUartPort(const unsigned int port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size) - : kPortName(PortName(port_id)), baud_rate_(baud_rate), kTxBufferSize(tx_buffer_size), kRxBufferSize(rx_buffer_size) { + : kPortName(GetPortName(port_id)), baud_rate_(baud_rate), kTxBufferSize(tx_buffer_size), kRxBufferSize(rx_buffer_size) { // Allocate managed arrays. tx_buffer_ = gcnew bytearray(kTxBufferSize); rx_buffer_ = gcnew bytearray(kRxBufferSize); @@ -25,7 +25,7 @@ HilsUartPort::~HilsUartPort() { } // Static method to convert from com port number to com port name. -std::string HilsUartPort::PortName(const unsigned int port_id) { return "COM" + std::to_string(port_id); } +std::string HilsUartPort::GetPortName(const unsigned int port_id) { return "COM" + std::to_string(port_id); } int HilsUartPort::Initialize() { try { diff --git a/src/components/ports/hils_uart_port.hpp b/src/components/ports/hils_uart_port.hpp index d3e45ba3a..1be6a9b8f 100644 --- a/src/components/ports/hils_uart_port.hpp +++ b/src/components/ports/hils_uart_port.hpp @@ -88,12 +88,12 @@ class HilsUartPort { msclr::gcroot rx_buffer_; //!< RX Buffer /** - * @fn PortName + * @fn GetPortName * @brief Convert port id to port name * @param [in] port_id: Port ID like 4 * @return Port name like "COM4" */ - static std::string PortName(const unsigned int port_id); + static std::string GetPortName(const unsigned int port_id); /** * @fn Initialize * @brief Open and initialize the COM port From 689c13850a17af1008eff162c586ca009a6aac51 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:13:46 +0100 Subject: [PATCH 0759/1086] Rename GPIOPort to GpioPort --- src/components/ports/gpio_port.cpp | 8 ++++---- src/components/ports/gpio_port.hpp | 12 ++++++------ src/components/real/cdh/on_board_computer.cpp | 6 +++--- src/components/real/cdh/on_board_computer.hpp | 2 +- .../real/cdh/on_board_computer_with_c2a.cpp | 12 ++++++------ .../real/cdh/on_board_computer_with_c2a.hpp | 2 +- 6 files changed, 21 insertions(+), 21 deletions(-) diff --git a/src/components/ports/gpio_port.cpp b/src/components/ports/gpio_port.cpp index 75ddc02c7..4a155cc57 100644 --- a/src/components/ports/gpio_port.cpp +++ b/src/components/ports/gpio_port.cpp @@ -5,14 +5,14 @@ #include "gpio_port.hpp" -GPIOPort::GPIOPort(const unsigned int port_id, IGPIOCompo* component) : kPortId(port_id) { +GpioPort::GpioPort(const unsigned int port_id, IGPIOCompo* component) : kPortId(port_id) { high_low_state_ = GPIO_LOW; component_ = component; } -GPIOPort::~GPIOPort() {} +GpioPort::~GpioPort() {} -int GPIOPort::DigitalWrite(const bool is_high) { +int GpioPort::DigitalWrite(const bool is_high) { if (high_low_state_ != is_high) { // Call interaction function when detecting the change of the HIGH/LOW state if (component_ != nullptr) { @@ -23,4 +23,4 @@ int GPIOPort::DigitalWrite(const bool is_high) { return 0; } -bool GPIOPort::DigitalRead() { return high_low_state_; } +bool GpioPort::DigitalRead() { return high_low_state_; } diff --git a/src/components/ports/gpio_port.hpp b/src/components/ports/gpio_port.hpp index 8eec58b93..b1c38bb2a 100644 --- a/src/components/ports/gpio_port.hpp +++ b/src/components/ports/gpio_port.hpp @@ -12,23 +12,23 @@ #define GPIO_LOW false /** - * @class GPIOPort + * @class GpioPort * @brief Class to emulate GPIO(General Purpose Input and Output) port */ -class GPIOPort { +class GpioPort { public: /** - * @fn GPIOPort + * @fn GpioPort * @brief Constructor * @param [in] port_id_: ID of the GPIO port * @param [in] component: Component which has the GPIO port */ - GPIOPort(const unsigned int port_id_, IGPIOCompo* component = nullptr); + GpioPort(const unsigned int port_id_, IGPIOCompo* component = nullptr); /** - * @fn ~GPIOPort + * @fn ~GpioPort * @brief Destructor */ - ~GPIOPort(); + ~GpioPort(); /** * @fn DigitalWrite diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index b93665f8e..653e44b73 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -113,18 +113,18 @@ int OBC::GpioConnectPort(int port_id) { // Port already used return -1; } - gpio_ports_[port_id] = new GPIOPort(port_id); + gpio_ports_[port_id] = new GpioPort(port_id); return 0; } int OBC::GpioComponentWrite(int port_id, const bool is_high) { - GPIOPort* port = gpio_ports_[port_id]; + GpioPort* port = gpio_ports_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } bool OBC::GpioComponentRead(int port_id) { - GPIOPort* port = gpio_ports_[port_id]; + GpioPort* port = gpio_ports_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index e4ef7bf86..3773a7a62 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -203,7 +203,7 @@ class OBC : public Component { private: std::map com_ports_; //!< UART ports std::map i2c_com_ports_; //!< I2C ports - std::map gpio_ports_; //!< GPIO ports + std::map gpio_ports_; //!< GPIO ports }; #endif // S2E_COMPONENTS_REAL_CDH_OBC_HPP_ diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index 5a2461651..e5da960c3 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -14,7 +14,7 @@ std::map OBC_C2A::com_ports_c2a_; std::map OBC_C2A::i2c_com_ports_c2a_; -std::map OBC_C2A::gpio_ports_c2a_; +std::map OBC_C2A::gpio_ports_c2a_; OBC_C2A::OBC_C2A(ClockGenerator* clock_gen) : OBC(clock_gen), timing_regulator_(1) { // Initialize(); @@ -207,30 +207,30 @@ int OBC_C2A::GpioConnectPort(int port_id) { // Port already used return -1; } - gpio_ports_c2a_[port_id] = new GPIOPort(port_id); + gpio_ports_c2a_[port_id] = new GpioPort(port_id); return 0; } int OBC_C2A::GpioComponentWrite(int port_id, const bool is_high) { - GPIOPort* port = gpio_ports_c2a_[port_id]; + GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } bool OBC_C2A::GpioComponentRead(int port_id) { - GPIOPort* port = gpio_ports_c2a_[port_id]; + GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); } int OBC_C2A::GpioWrite_C2A(int port_id, const bool is_high) { - GPIOPort* port = gpio_ports_c2a_[port_id]; + GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } bool OBC_C2A::GpioRead_C2A(int port_id) { - GPIOPort* port = gpio_ports_c2a_[port_id]; + GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 1f1164bd1..52b5a8e5b 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -267,7 +267,7 @@ class OBC_C2A : public OBC { static std::map com_ports_c2a_; //!< UART ports static std::map i2c_com_ports_c2a_; //!< I2C ports - static std::map gpio_ports_c2a_; //!< GPIO ports + static std::map gpio_ports_c2a_; //!< GPIO ports }; // If the character encoding of C2A is UTF-8, the following functions are not necessary, From 0cbc2519bf7177f369dc4586ef01fc0dd11e8846 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:14:20 +0100 Subject: [PATCH 0760/1086] Move public const to private const --- src/components/ports/i2c_port.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 8c27e1dca..284c1ea11 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -8,8 +8,6 @@ #include -const int kDefaultCmdBufferSize = 0xff; //!< Default command buffer size - /** * @class I2CPort * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port @@ -99,6 +97,7 @@ class I2CPort { unsigned char ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length); private: + const int kDefaultCmdBufferSize = 0xff; //!< Default command buffer size unsigned char max_register_number_ = 0xff; //!< Maximum register number unsigned char saved_register_address_ = 0x00; //!< Saved register address From da3538a8058ef603157bd13cea9079a967bf8d34 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:15:22 +0100 Subject: [PATCH 0761/1086] Rename I2CPort to I2cPort --- src/components/ports/i2c_port.cpp | 20 +++++++++---------- src/components/ports/i2c_port.hpp | 12 +++++------ src/components/real/cdh/on_board_computer.cpp | 10 +++++----- src/components/real/cdh/on_board_computer.hpp | 2 +- .../real/cdh/on_board_computer_with_c2a.cpp | 18 ++++++++--------- .../real/cdh/on_board_computer_with_c2a.hpp | 2 +- 6 files changed, 32 insertions(+), 32 deletions(-) diff --git a/src/components/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp index 05bec10f0..9c0420ee6 100644 --- a/src/components/ports/i2c_port.cpp +++ b/src/components/ports/i2c_port.cpp @@ -7,11 +7,11 @@ #include -I2CPort::I2CPort(void) {} +I2cPort::I2cPort(void) {} -I2CPort::I2CPort(const unsigned char max_register_number) : max_register_number_(max_register_number) {} +I2cPort::I2cPort(const unsigned char max_register_number) : max_register_number_(max_register_number) {} -void I2CPort::RegisterDevice(const unsigned char i2c_addr) { +void I2cPort::RegisterDevice(const unsigned char i2c_addr) { for (unsigned char i = 0; i < max_register_number_; i++) { device_registers_[std::make_pair(i2c_addr, i)] = 0x00; } @@ -20,7 +20,7 @@ void I2CPort::RegisterDevice(const unsigned char i2c_addr) { } } -int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address) { +int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address) { UNUSED(i2c_addr); // TODO: consider this argument is really needed. if (register_address >= max_register_number_) return 0; @@ -28,7 +28,7 @@ int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg return 1; } -int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value) { +int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value) { if (register_address >= max_register_number_) return 0; saved_register_address_ = register_address; device_registers_[std::make_pair(i2c_addr, register_address)] = value; @@ -36,7 +36,7 @@ int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char reg } /* -int I2CPort::WriteRegister(const unsigned char i2c_addr, const unsigned char +int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, float value) { if(register_address >= max_register_number_) return 0; @@ -50,21 +50,21 @@ register_address, float value) } */ -unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr) { +unsigned char I2cPort::ReadRegister(const unsigned char i2c_addr) { unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; saved_register_address_++; if (saved_register_address_ >= max_register_number_) saved_register_address_ = 0; return ret; } -unsigned char I2CPort::ReadRegister(const unsigned char i2c_addr, const unsigned char register_address) { +unsigned char I2cPort::ReadRegister(const unsigned char i2c_addr, const unsigned char register_address) { if (register_address >= max_register_number_) return 0; saved_register_address_ = register_address; unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; return ret; } -unsigned char I2CPort::WriteCommand(const unsigned char i2c_addr, const unsigned char* tx_data, const unsigned char length) { +unsigned char I2cPort::WriteCommand(const unsigned char i2c_addr, const unsigned char* tx_data, const unsigned char length) { if (length > kDefaultCmdBufferSize) { return 0; } @@ -84,7 +84,7 @@ unsigned char I2CPort::WriteCommand(const unsigned char i2c_addr, const unsigned return length; } -unsigned char I2CPort::ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length) { +unsigned char I2cPort::ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length) { if (length > kDefaultCmdBufferSize) { return 0; } diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 284c1ea11..173db106c 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -9,23 +9,23 @@ #include /** - * @class I2CPort + * @class I2cPort * @brief Class to emulate I2C(Inter-Integrated Circuit) communication port * @details The class has the register to store the parameters */ -class I2CPort { +class I2cPort { public: /** - * @fn I2CPort + * @fn I2cPort * @brief Default Constructor. Nothing happened. */ - I2CPort(void); + I2cPort(void); /** - * @fn I2CPort + * @fn I2cPort * @brief Constructor. Just set the max_register_number. * @param [in] max_register_number: Maximum register number */ - I2CPort(const unsigned char max_register_number); + I2cPort(const unsigned char max_register_number); /** * @fn RegisterDevice diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index 653e44b73..d5afe1d75 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -69,7 +69,7 @@ int OBC::I2cConnectPort(int port_id, const unsigned char i2c_addr) { if (i2c_com_ports_[port_id] != nullptr) { // Port already used } else { - i2c_com_ports_[port_id] = new I2CPort(); + i2c_com_ports_[port_id] = new I2cPort(); } i2c_com_ports_[port_id]->RegisterDevice(i2c_addr); @@ -80,7 +80,7 @@ int OBC::I2cCloseComPort(int port_id) { // Port not used if (i2c_com_ports_[port_id] == nullptr) return -1; - I2CPort* port = i2c_com_ports_.at(port_id); + I2cPort* port = i2c_com_ports_.at(port_id); delete port; i2c_com_ports_.erase(port_id); return 0; @@ -88,7 +88,7 @@ int OBC::I2cCloseComPort(int port_id) { int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_com_ports_[port_id]; for (int i = 0; i < len; i++) { i2c_port->WriteRegister(i2c_addr, reg_addr, data[i]); } @@ -96,14 +96,14 @@ int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, co } int OBC::I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_com_ports_[port_id]; for (int i = 0; i < len; i++) { data[i] = i2c_port->ReadRegister(reg_addr, i2c_addr); } return 0; } int OBC::I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_com_ports_[port_id]; i2c_port->ReadCommand(i2c_addr, data, len); return 0; } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 3773a7a62..d35316c2b 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -202,7 +202,7 @@ class OBC : public Component { private: std::map com_ports_; //!< UART ports - std::map i2c_com_ports_; //!< I2C ports + std::map i2c_com_ports_; //!< I2C ports std::map gpio_ports_; //!< GPIO ports }; diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index e5da960c3..0c158ece2 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -13,7 +13,7 @@ #endif std::map OBC_C2A::com_ports_c2a_; -std::map OBC_C2A::i2c_com_ports_c2a_; +std::map OBC_C2A::i2c_com_ports_c2a_; std::map OBC_C2A::gpio_ports_c2a_; OBC_C2A::OBC_C2A(ClockGenerator* clock_gen) : OBC(clock_gen), timing_regulator_(1) { @@ -126,7 +126,7 @@ int OBC_C2A::I2cConnectPort(int port_id, const unsigned char i2c_addr) { if (i2c_com_ports_c2a_[port_id] != nullptr) { // Port already used } else { - i2c_com_ports_c2a_[port_id] = new I2CPort(); + i2c_com_ports_c2a_[port_id] = new I2cPort(); } i2c_com_ports_c2a_[port_id]->RegisterDevice(i2c_addr); @@ -137,20 +137,20 @@ int OBC_C2A::I2cCloseComPort(int port_id) { // Port not used if (i2c_com_ports_c2a_[port_id] == nullptr) return -1; - I2CPort* port = i2c_com_ports_c2a_.at(port_id); + I2cPort* port = i2c_com_ports_c2a_.at(port_id); delete port; i2c_com_ports_c2a_.erase(port_id); return 0; } int OBC_C2A::I2cWriteCommand(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; i2c_port->WriteCommand(i2c_addr, data, len); return 0; } int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; if (len == 1) { i2c_port->WriteRegister(i2c_addr, data[0]); @@ -163,7 +163,7 @@ int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_addr, const u } int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (int i = 0; i < len; i++) { data[i] = i2c_port->ReadRegister(i2c_addr); } @@ -172,7 +172,7 @@ int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned int OBC_C2A::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < len; i++) { i2c_port->WriteRegister(i2c_addr, reg_addr + i, data[i]); } @@ -180,14 +180,14 @@ int OBC_C2A::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr } int OBC_C2A::I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < len; i++) { data[i] = i2c_port->ReadRegister(i2c_addr, reg_addr + i); } return 0; } int OBC_C2A::I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { - I2CPort* i2c_port = i2c_com_ports_c2a_[port_id]; + I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; i2c_port->ReadCommand(i2c_addr, data, len); return 0; } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 52b5a8e5b..62b39c4f7 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -266,7 +266,7 @@ class OBC_C2A : public OBC { void Initialize(); static std::map com_ports_c2a_; //!< UART ports - static std::map i2c_com_ports_c2a_; //!< I2C ports + static std::map i2c_com_ports_c2a_; //!< I2C ports static std::map gpio_ports_c2a_; //!< GPIO ports }; From b79eed9f4fd3d67883ce9a7625b51beec75743c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:16:24 +0100 Subject: [PATCH 0762/1086] Fix function argument variables --- src/components/ports/i2c_port.cpp | 38 +++++++++++++++---------------- src/components/ports/i2c_port.hpp | 30 ++++++++++++------------ 2 files changed, 34 insertions(+), 34 deletions(-) diff --git a/src/components/ports/i2c_port.cpp b/src/components/ports/i2c_port.cpp index 9c0420ee6..d01b5b21d 100644 --- a/src/components/ports/i2c_port.cpp +++ b/src/components/ports/i2c_port.cpp @@ -11,32 +11,32 @@ I2cPort::I2cPort(void) {} I2cPort::I2cPort(const unsigned char max_register_number) : max_register_number_(max_register_number) {} -void I2cPort::RegisterDevice(const unsigned char i2c_addr) { +void I2cPort::RegisterDevice(const unsigned char i2c_address) { for (unsigned char i = 0; i < max_register_number_; i++) { - device_registers_[std::make_pair(i2c_addr, i)] = 0x00; + device_registers_[std::make_pair(i2c_address, i)] = 0x00; } for (unsigned char i = 0; i < kDefaultCmdBufferSize; i++) { - command_buffer_[std::make_pair(i2c_addr, i)] = 0x00; + command_buffer_[std::make_pair(i2c_address, i)] = 0x00; } } -int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address) { - UNUSED(i2c_addr); // TODO: consider this argument is really needed. +int I2cPort::WriteRegister(const unsigned char i2c_address, const unsigned char register_address) { + UNUSED(i2c_address); // TODO: consider this argument is really needed. if (register_address >= max_register_number_) return 0; saved_register_address_ = register_address; return 1; } -int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value) { +int I2cPort::WriteRegister(const unsigned char i2c_address, const unsigned char register_address, const unsigned char value) { if (register_address >= max_register_number_) return 0; saved_register_address_ = register_address; - device_registers_[std::make_pair(i2c_addr, register_address)] = value; + device_registers_[std::make_pair(i2c_address, register_address)] = value; return 1; } /* -int I2cPort::WriteRegister(const unsigned char i2c_addr, const unsigned char +int I2cPort::WriteRegister(const unsigned char i2c_address, const unsigned char register_address, float value) { if(register_address >= max_register_number_) return 0; @@ -44,52 +44,52 @@ register_address, float value) unsigned char* value_ptr = reinterpret_cast(&value); for(size_t i = 0; i < sizeof(float); i++) { - WriteRegister(i2c_addr,register_address, value_ptr[i]); + WriteRegister(i2c_address,register_address, value_ptr[i]); } return 1; } */ -unsigned char I2cPort::ReadRegister(const unsigned char i2c_addr) { - unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; +unsigned char I2cPort::ReadRegister(const unsigned char i2c_address) { + unsigned char ret = device_registers_[std::make_pair(i2c_address, saved_register_address_)]; saved_register_address_++; if (saved_register_address_ >= max_register_number_) saved_register_address_ = 0; return ret; } -unsigned char I2cPort::ReadRegister(const unsigned char i2c_addr, const unsigned char register_address) { +unsigned char I2cPort::ReadRegister(const unsigned char i2c_address, const unsigned char register_address) { if (register_address >= max_register_number_) return 0; saved_register_address_ = register_address; - unsigned char ret = device_registers_[std::make_pair(i2c_addr, saved_register_address_)]; + unsigned char ret = device_registers_[std::make_pair(i2c_address, saved_register_address_)]; return ret; } -unsigned char I2cPort::WriteCommand(const unsigned char i2c_addr, const unsigned char* tx_data, const unsigned char length) { +unsigned char I2cPort::WriteCommand(const unsigned char i2c_address, const unsigned char* tx_data, const unsigned char length) { if (length > kDefaultCmdBufferSize) { return 0; } for (unsigned char i = 0; i < length; i++) { - command_buffer_[std::make_pair(i2c_addr, i)] = tx_data[i]; + command_buffer_[std::make_pair(i2c_address, i)] = tx_data[i]; } if (length == 1) // length == 1 means setting of read register address { - WriteRegister(i2c_addr, tx_data[0]); + WriteRegister(i2c_address, tx_data[0]); } if (length == 2) // length ==2 means setting specific register. FIXME: this rule is not general. { - WriteRegister(i2c_addr, tx_data[0], tx_data[1]); + WriteRegister(i2c_address, tx_data[0], tx_data[1]); } return length; } -unsigned char I2cPort::ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length) { +unsigned char I2cPort::ReadCommand(const unsigned char i2c_address, unsigned char* rx_data, const unsigned char length) { if (length > kDefaultCmdBufferSize) { return 0; } for (unsigned char i = 0; i < length; i++) { - rx_data[i] = command_buffer_[std::make_pair(i2c_addr, i)]; + rx_data[i] = command_buffer_[std::make_pair(i2c_address, i)]; } return length; } diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 173db106c..587786419 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -32,69 +32,69 @@ class I2cPort { * @brief Register the device as an I2C port. * @param [in] i2c_address: I2C address */ - void RegisterDevice(const unsigned char i2c_addr); + void RegisterDevice(const unsigned char i2c_address); /** * @fn WriteRegister * @brief Set the register address to write a value in the next step - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] register_address: Register address to write a value in the next step * @return Return zero when an error is happened. */ - int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address); + int WriteRegister(const unsigned char i2c_address, const unsigned char register_address); /** * @fn WriteRegister * @brief Write a value in the target device's register - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] register_address: Register address of the target device * @param [in] value: 1 Byte value * @return Return zero when an error is happened. */ - int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, const unsigned char value); + int WriteRegister(const unsigned char i2c_address, const unsigned char register_address, const unsigned char value); /** * @fn WriteRegister * @brief Write a value in the target device's register - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] register_address: Register address of the target device * @param [in] value: float value */ - // int WriteRegister(const unsigned char i2c_addr, const unsigned char register_address, float value); // TODO Check this works well + // int WriteRegister(const unsigned char i2c_address, const unsigned char register_address, float value); // TODO Check this works well /** * @fn ReadRegister * @brief Read the register value of the target device. The register address is used as the previous accessed address - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @return Read data */ - unsigned char ReadRegister(const unsigned char i2c_addr); + unsigned char ReadRegister(const unsigned char i2c_address); /** * @fn ReadRegister * @brief Read the register value of the target device. - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] register_address: Register address of the target device * @return Read data */ - unsigned char ReadRegister(const unsigned char i2c_addr, const unsigned char register_address); + unsigned char ReadRegister(const unsigned char i2c_address, const unsigned char register_address); // OBC->Component Command emulation /** * @fn WriteCommand * @brief Write command requested from an OBC to the component - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] tx_data: data from the OBC * @param [in] length: length of the tx_data * @return Length or zero when an error happened */ - unsigned char WriteCommand(const unsigned char i2c_addr, const unsigned char* tx_data, const unsigned char length); + unsigned char WriteCommand(const unsigned char i2c_address, const unsigned char* tx_data, const unsigned char length); /** * @fn ReadCommand * @brief Read command requested from an OBC to the component - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [out] rx_data: Data to the OBC * @param [in] length: Length of the tx_data * @return Length or zero when an error happened */ - unsigned char ReadCommand(const unsigned char i2c_addr, unsigned char* rx_data, const unsigned char length); + unsigned char ReadCommand(const unsigned char i2c_address, unsigned char* rx_data, const unsigned char length); private: const int kDefaultCmdBufferSize = 0xff; //!< Default command buffer size From 3f2e9986ff72c09b07d09cb65952b7f3d3141321 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:23:44 +0100 Subject: [PATCH 0763/1086] Fix private variables --- src/components/ports/power_port.cpp | 31 ++++++++++++++++------------- src/components/ports/power_port.hpp | 28 +++++++++++++------------- 2 files changed, 31 insertions(+), 28 deletions(-) diff --git a/src/components/ports/power_port.cpp b/src/components/ports/power_port.cpp index 0fe84a373..b656cb820 100644 --- a/src/components/ports/power_port.cpp +++ b/src/components/ports/power_port.cpp @@ -8,55 +8,58 @@ #include #include -PowerPort::PowerPort() : kPortId(-1), current_limit_(10.0), minimum_voltage_(3.3), assumed_power_consumption_(0.0) { +PowerPort::PowerPort() : kPortId(-1), current_limit_A_(10.0), minimum_voltage_V_(3.3), assumed_power_consumption_W_(0.0) { is_on_ = true; // power on to work the component Initialize(); } PowerPort::PowerPort(int port_id, double current_Limit) - : kPortId(port_id), current_limit_(current_Limit), minimum_voltage_(3.3), assumed_power_consumption_(0.0) { + : kPortId(port_id), current_limit_A_(current_Limit), minimum_voltage_V_(3.3), assumed_power_consumption_W_(0.0) { Initialize(); } PowerPort::PowerPort(int port_id, double current_Limit, double minimum_voltage, double assumed_power_consumption) - : kPortId(port_id), current_limit_(current_Limit), minimum_voltage_(minimum_voltage), assumed_power_consumption_(assumed_power_consumption) { + : kPortId(port_id), + current_limit_A_(current_Limit), + minimum_voltage_V_(minimum_voltage), + assumed_power_consumption_W_(assumed_power_consumption) { Initialize(); } PowerPort::~PowerPort() {} void PowerPort::Initialize(void) { - voltage_ = 0.0f; - current_consumption_ = 0.0f; + voltage_V_ = 0.0f; + current_consumption_A_ = 0.0f; } bool PowerPort::Update(void) { // switching - if (voltage_ >= (minimum_voltage_ - DBL_EPSILON)) { + if (voltage_V_ >= (minimum_voltage_V_ - DBL_EPSILON)) { is_on_ = true; - current_consumption_ = assumed_power_consumption_ / voltage_; + current_consumption_A_ = assumed_power_consumption_W_ / voltage_V_; } else { - current_consumption_ = 0.0; + current_consumption_A_ = 0.0; is_on_ = false; } // over current protection - if (current_consumption_ >= (current_limit_ - DBL_EPSILON)) { - current_consumption_ = 0.0; - voltage_ = 0.0; + if (current_consumption_A_ >= (current_limit_A_ - DBL_EPSILON)) { + current_consumption_A_ = 0.0; + voltage_V_ = 0.0; is_on_ = false; } return is_on_; } bool PowerPort::SetVoltage(const double voltage) { - voltage_ = voltage; + voltage_V_ = voltage; Update(); return is_on_; } void PowerPort::SubtractAssumedPowerConsumption(const double power) { - assumed_power_consumption_ -= power; - if (assumed_power_consumption_ < 0.0) assumed_power_consumption_ = 0.0; + assumed_power_consumption_W_ -= power; + if (assumed_power_consumption_W_ < 0.0) assumed_power_consumption_W_ = 0.0; return; } diff --git a/src/components/ports/power_port.hpp b/src/components/ports/power_port.hpp index cba13af2e..cfd2e6d83 100644 --- a/src/components/ports/power_port.hpp +++ b/src/components/ports/power_port.hpp @@ -55,17 +55,17 @@ class PowerPort { * @fn GetVoltage * @brief Return the voltage of this power line [V] */ - inline double GetVoltage(void) const { return voltage_; } + inline double GetVoltage(void) const { return voltage_V_; } /** * @fn GetCurrentConsumption * @brief Return the current consumption of this power line [A] */ - inline double GetCurrentConsumption() const { return current_consumption_; } + inline double GetCurrentConsumption() const { return current_consumption_A_; } /** * @fn GetAssumedPowerConsumption * @brief Return the assumed power consumption of this power line [W] */ - inline double GetAssumedPowerConsumption() const { return assumed_power_consumption_; } + inline double GetAssumedPowerConsumption() const { return assumed_power_consumption_W_; } /** * @fn GetIsOn * @brief Return the power switch state @@ -84,24 +84,24 @@ class PowerPort { * @brief Set assumed power consumption [W] * @note Users can use this function to change the power consumption of the component depending on the execution state. */ - inline void SetAssumedPowerConsumption(const double power) { assumed_power_consumption_ = power; } + inline void SetAssumedPowerConsumption(const double power) { assumed_power_consumption_W_ = power; } /** * @fn SetMinimumVoltage * @brief Set minimum voltage to work the component [V] */ - inline void SetMinimumVoltage(const double minimum_voltage) { minimum_voltage_ = minimum_voltage; } + inline void SetMinimumVoltage(const double minimum_voltage) { minimum_voltage_V_ = minimum_voltage; } /** * @fn SetCurrentLimit * @brief Set threshold to detect over current [A] */ - inline void SetCurrentLimit(const double current_limit) { current_limit_ = current_limit; } + inline void SetCurrentLimit(const double current_limit) { current_limit_A_ = current_limit; } // Others /** * @fn AddAssumedPowerConsumption * @brief Add assumed power consumption [W] to emulate power line which has multiple loads */ - inline void AddAssumedPowerConsumption(const double power) { assumed_power_consumption_ += power; } + inline void AddAssumedPowerConsumption(const double power) { assumed_power_consumption_W_ += power; } /** * @fn SubtractAssumedPowerConsumption * @brief Subtract assumed power consumption [W] to emulate power line which has multiple loads @@ -115,16 +115,16 @@ class PowerPort { private: // PCU setting parameters - const int kPortId; //!< ID of the power port - double current_limit_; //!< Threshold to detect over current [A] + const int kPortId; //!< ID of the power port + double current_limit_A_; //!< Threshold to detect over current [A] // Components setting parameters - double minimum_voltage_; //!< Minimum voltage to work the component [V] - double assumed_power_consumption_; //!< Assumed power consumption of the component [W] + double minimum_voltage_V_; //!< Minimum voltage to work the component [V] + double assumed_power_consumption_W_; //!< Assumed power consumption of the component [W] - double voltage_; //!< Voltage of the power line[V] - double current_consumption_; //!< Current consumption calculated by I = P/V[A] - bool is_on_; //!< Power switch state + double voltage_V_; //!< Voltage of the power line[V] + double current_consumption_A_; //!< Current consumption calculated by I = P/V[A] + bool is_on_; //!< Power switch state /** * @fn Initialize From 521a2730b2909f369435d2d5f2cc8b9289661794 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:26:57 +0100 Subject: [PATCH 0764/1086] Fix function argument variables --- src/components/ports/power_port.cpp | 8 ++++---- src/components/ports/power_port.hpp | 20 ++++++++++---------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/ports/power_port.cpp b/src/components/ports/power_port.cpp index b656cb820..712a12a32 100644 --- a/src/components/ports/power_port.cpp +++ b/src/components/ports/power_port.cpp @@ -51,14 +51,14 @@ bool PowerPort::Update(void) { return is_on_; } -bool PowerPort::SetVoltage(const double voltage) { - voltage_V_ = voltage; +bool PowerPort::SetVoltage(const double voltage_V) { + voltage_V_ = voltage_V; Update(); return is_on_; } -void PowerPort::SubtractAssumedPowerConsumption(const double power) { - assumed_power_consumption_W_ -= power; +void PowerPort::SubtractAssumedPowerConsumption(const double power_W) { + assumed_power_consumption_W_ -= power_W; if (assumed_power_consumption_W_ < 0.0) assumed_power_consumption_W_ = 0.0; return; } diff --git a/src/components/ports/power_port.hpp b/src/components/ports/power_port.hpp index cfd2e6d83..81230b8c7 100644 --- a/src/components/ports/power_port.hpp +++ b/src/components/ports/power_port.hpp @@ -33,7 +33,7 @@ class PowerPort { * @brief Constructor * @param [in] port_id: ID of the power port * @param [in] current_Limit: Threshold to detect over current [A] - * @param [in] minimum_voltage: Minimum voltage to work the component [V] + * @param [in] minimum_voltage: Minimum voltage_V to work the component [V] * @param [in] assumed_power_consumption: Assumed power consumption of the component [W] */ PowerPort(int port_id, double current_Limit, double minimum_voltage, double assumed_power_consumption); @@ -53,7 +53,7 @@ class PowerPort { // Getters /** * @fn GetVoltage - * @brief Return the voltage of this power line [V] + * @brief Return the voltage_V of this power line [V] */ inline double GetVoltage(void) const { return voltage_V_; } /** @@ -75,38 +75,38 @@ class PowerPort { // Setters /** * @fn SetVoltage - * @brief Set voltage to control the power switch state + * @brief Set voltage_V to control the power switch state * @return Power switch state */ - bool SetVoltage(const double voltage); + bool SetVoltage(const double voltage_V); /** * @fn SetAssumedPowerConsumption * @brief Set assumed power consumption [W] * @note Users can use this function to change the power consumption of the component depending on the execution state. */ - inline void SetAssumedPowerConsumption(const double power) { assumed_power_consumption_W_ = power; } + inline void SetAssumedPowerConsumption(const double power_W) { assumed_power_consumption_W_ = power_W; } /** * @fn SetMinimumVoltage * @brief Set minimum voltage to work the component [V] */ - inline void SetMinimumVoltage(const double minimum_voltage) { minimum_voltage_V_ = minimum_voltage; } + inline void SetMinimumVoltage(const double minimum_voltage_V) { minimum_voltage_V_ = minimum_voltage_V; } /** * @fn SetCurrentLimit * @brief Set threshold to detect over current [A] */ - inline void SetCurrentLimit(const double current_limit) { current_limit_A_ = current_limit; } + inline void SetCurrentLimit(const double current_limit_A) { current_limit_A_ = current_limit_A; } // Others /** * @fn AddAssumedPowerConsumption * @brief Add assumed power consumption [W] to emulate power line which has multiple loads */ - inline void AddAssumedPowerConsumption(const double power) { assumed_power_consumption_W_ += power; } + inline void AddAssumedPowerConsumption(const double power_W) { assumed_power_consumption_W_ += power_W; } /** * @fn SubtractAssumedPowerConsumption * @brief Subtract assumed power consumption [W] to emulate power line which has multiple loads */ - void SubtractAssumedPowerConsumption(const double power); + void SubtractAssumedPowerConsumption(const double power_W); /** * @fn InitializeWithInitializeFile * @brief Initialize PowerPort class with initialize file @@ -119,7 +119,7 @@ class PowerPort { double current_limit_A_; //!< Threshold to detect over current [A] // Components setting parameters - double minimum_voltage_V_; //!< Minimum voltage to work the component [V] + double minimum_voltage_V_; //!< Minimum voltage_V to work the component [V] double assumed_power_consumption_W_; //!< Assumed power consumption of the component [W] double voltage_V_; //!< Voltage of the power line[V] From a95cb26d4de757176b1a49e1f4e136883c9a9dfb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:32:54 +0100 Subject: [PATCH 0765/1086] Fix public function name --- src/components/ports/power_port.cpp | 24 +++++----- src/components/ports/power_port.hpp | 48 +++++++++---------- src/components/real/cdh/on_board_computer.cpp | 4 +- .../real/power/pcu_initial_study.cpp | 2 +- .../real/power/power_control_unit.cpp | 2 +- .../real/power/solar_array_panel.cpp | 2 +- .../real/power/solar_array_panel.hpp | 4 +- .../sample_spacecraft/sample_components.cpp | 6 +-- 8 files changed, 46 insertions(+), 46 deletions(-) diff --git a/src/components/ports/power_port.cpp b/src/components/ports/power_port.cpp index 712a12a32..2989111a5 100644 --- a/src/components/ports/power_port.cpp +++ b/src/components/ports/power_port.cpp @@ -13,16 +13,16 @@ PowerPort::PowerPort() : kPortId(-1), current_limit_A_(10.0), minimum_voltage_V_ Initialize(); } -PowerPort::PowerPort(int port_id, double current_Limit) - : kPortId(port_id), current_limit_A_(current_Limit), minimum_voltage_V_(3.3), assumed_power_consumption_W_(0.0) { +PowerPort::PowerPort(const int port_id, const double current_limit_A) + : kPortId(port_id), current_limit_A_(current_limit_A), minimum_voltage_V_(3.3), assumed_power_consumption_W_(0.0) { Initialize(); } -PowerPort::PowerPort(int port_id, double current_Limit, double minimum_voltage, double assumed_power_consumption) +PowerPort::PowerPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W) : kPortId(port_id), - current_limit_A_(current_Limit), - minimum_voltage_V_(minimum_voltage), - assumed_power_consumption_W_(assumed_power_consumption) { + current_limit_A_(current_limit_A), + minimum_voltage_V_(minimum_voltage_V), + assumed_power_consumption_W_(assumed_power_consumption_W) { Initialize(); } @@ -51,13 +51,13 @@ bool PowerPort::Update(void) { return is_on_; } -bool PowerPort::SetVoltage(const double voltage_V) { +bool PowerPort::SetVoltage_V(const double voltage_V) { voltage_V_ = voltage_V; Update(); return is_on_; } -void PowerPort::SubtractAssumedPowerConsumption(const double power_W) { +void PowerPort::SubtractAssumedPowerConsumption_W(const double power_W) { assumed_power_consumption_W_ -= power_W; if (assumed_power_consumption_W_ < 0.0) assumed_power_consumption_W_ = 0.0; return; @@ -67,8 +67,8 @@ void PowerPort::InitializeWithInitializeFile(const std::string file_name) { IniAccess initialize_file(file_name); const std::string section_name = "POWER_PORT"; - double minimum_voltage = initialize_file.ReadDouble(section_name.c_str(), "minimum_voltage_V"); - this->SetMinimumVoltage(minimum_voltage); - double assumed_power_consumption = initialize_file.ReadDouble(section_name.c_str(), "assumed_power_consumption_W"); - this->SetAssumedPowerConsumption(assumed_power_consumption); + double minimum_voltage_V = initialize_file.ReadDouble(section_name.c_str(), "minimum_voltage_V"); + this->SetMinimumVoltage_V(minimum_voltage_V); + double assumed_power_consumption_W = initialize_file.ReadDouble(section_name.c_str(), "assumed_power_consumption_W"); + this->SetAssumedPowerConsumption_W(assumed_power_consumption_W); } diff --git a/src/components/ports/power_port.hpp b/src/components/ports/power_port.hpp index 81230b8c7..e890d25b5 100644 --- a/src/components/ports/power_port.hpp +++ b/src/components/ports/power_port.hpp @@ -25,18 +25,18 @@ class PowerPort { * @fn PowerPort * @brief Constructor * @param [in] port_id: ID of the power port - * @param [in] current_Limit: Threshold to detect over current [A] + * @param [in] current_limit_A: Threshold to detect over current [A] */ - PowerPort(int port_id, double current_Limit); + PowerPort(const int port_id, const double current_limit_A); /** * @fn PowerPort * @brief Constructor * @param [in] port_id: ID of the power port - * @param [in] current_Limit: Threshold to detect over current [A] - * @param [in] minimum_voltage: Minimum voltage_V to work the component [V] - * @param [in] assumed_power_consumption: Assumed power consumption of the component [W] + * @param [in] current_limit_A: Threshold to detect over current [A] + * @param [in] minimum_voltage_V: Minimum voltage_V to work the component [V] + * @param [in] assumed_power_consumption_W: Assumed power consumption of the component [W] */ - PowerPort(int port_id, double current_Limit, double minimum_voltage, double assumed_power_consumption); + PowerPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W); /** * @fn ~PowerPort * @brief Destructor @@ -52,20 +52,20 @@ class PowerPort { // Getters /** - * @fn GetVoltage + * @fn GetVoltage_V * @brief Return the voltage_V of this power line [V] */ - inline double GetVoltage(void) const { return voltage_V_; } + inline double GetVoltage_V(void) const { return voltage_V_; } /** - * @fn GetCurrentConsumption + * @fn GetCurrentConsumption_A * @brief Return the current consumption of this power line [A] */ - inline double GetCurrentConsumption() const { return current_consumption_A_; } + inline double GetCurrentConsumption_A() const { return current_consumption_A_; } /** - * @fn GetAssumedPowerConsumption + * @fn GetAssumedPowerConsumption_W * @brief Return the assumed power consumption of this power line [W] */ - inline double GetAssumedPowerConsumption() const { return assumed_power_consumption_W_; } + inline double GetAssumedPowerConsumption_W() const { return assumed_power_consumption_W_; } /** * @fn GetIsOn * @brief Return the power switch state @@ -74,39 +74,39 @@ class PowerPort { // Setters /** - * @fn SetVoltage + * @fn SetVoltage_V * @brief Set voltage_V to control the power switch state * @return Power switch state */ - bool SetVoltage(const double voltage_V); + bool SetVoltage_V(const double voltage_V); /** - * @fn SetAssumedPowerConsumption + * @fn SetAssumedPowerConsumption_W * @brief Set assumed power consumption [W] * @note Users can use this function to change the power consumption of the component depending on the execution state. */ - inline void SetAssumedPowerConsumption(const double power_W) { assumed_power_consumption_W_ = power_W; } + inline void SetAssumedPowerConsumption_W(const double power_W) { assumed_power_consumption_W_ = power_W; } /** - * @fn SetMinimumVoltage + * @fn SetMinimumVoltage_V * @brief Set minimum voltage to work the component [V] */ - inline void SetMinimumVoltage(const double minimum_voltage_V) { minimum_voltage_V_ = minimum_voltage_V; } + inline void SetMinimumVoltage_V(const double minimum_voltage_V) { minimum_voltage_V_ = minimum_voltage_V; } /** - * @fn SetCurrentLimit + * @fn SetCurrentLimit_A * @brief Set threshold to detect over current [A] */ - inline void SetCurrentLimit(const double current_limit_A) { current_limit_A_ = current_limit_A; } + inline void SetCurrentLimit_A(const double current_limit_A) { current_limit_A_ = current_limit_A; } // Others /** - * @fn AddAssumedPowerConsumption + * @fn AddAssumedPowerConsumption_W * @brief Add assumed power consumption [W] to emulate power line which has multiple loads */ - inline void AddAssumedPowerConsumption(const double power_W) { assumed_power_consumption_W_ += power_W; } + inline void AddAssumedPowerConsumption_W(const double power_W) { assumed_power_consumption_W_ += power_W; } /** - * @fn SubtractAssumedPowerConsumption + * @fn SubtractAssumedPowerConsumption_W * @brief Subtract assumed power consumption [W] to emulate power line which has multiple loads */ - void SubtractAssumedPowerConsumption(const double power_W); + void SubtractAssumedPowerConsumption_W(const double power_W); /** * @fn InitializeWithInitializeFile * @brief Initialize PowerPort class with initialize file diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index d5afe1d75..f8c555719 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -10,8 +10,8 @@ OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port) : Comp OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption) : Component(prescaler, clock_gen, power_port) { - power_port_->SetMinimumVoltage(minimum_voltage); - power_port_->SetAssumedPowerConsumption(assumed_power_consumption); + power_port_->SetMinimumVoltage_V(minimum_voltage); + power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption); Initialize(); } diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 0f0109b4a..b86b19aa9 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -54,7 +54,7 @@ void PCU_InitialStudy::MainRoutine(int time_count) { UpdateChargeCurrentAndBusVoltage(); for (auto sap : saps_) { - sap->SetVoltage(16.0); // Assume MPPT control + sap->SetVoltage_V(16.0); // Assume MPPT control } } diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index 087624a2b..0ca8e2692 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -13,7 +13,7 @@ PCU::~PCU() {} void PCU::MainRoutine(int count) { UNUSED(count); - // double current_ = ports_[1]->GetCurrentConsumption(); + // double current_ = ports_[1]->GetCurrentConsumption_A(); } int PCU::ConnectPort(const int port_id, const double current_Limit) { diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index cfcd697e6..16351caba 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -81,7 +81,7 @@ SAP::~SAP() {} double SAP::GetPowerGeneration() const { return power_generation_; } -void SAP::SetVoltage(const double voltage) { voltage_ = voltage; } +void SAP::SetVoltage_V(const double voltage) { voltage_ = voltage; } std::string SAP::GetLogHeader() const { std::string str_tmp = ""; diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 39dc57ab8..5ae3b795b 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -87,10 +87,10 @@ class SAP : public Component, public ILoggable { */ double GetPowerGeneration() const; /** - * @fn SetVoltage + * @fn SetVoltage_V * @brief Set voltage */ - void SetVoltage(const double voltage); + void SetVoltage_V(const double voltage); // Override ILoggable /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 5241b14fa..9475fff6f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -86,9 +86,9 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur antenna_ = new Antenna(InitAntenna(1, ini_path)); // PCU power port initial control - pcu_->GetPowerPort(0)->SetVoltage(3.3); - pcu_->GetPowerPort(1)->SetVoltage(3.3); - pcu_->GetPowerPort(2)->SetVoltage(3.3); + pcu_->GetPowerPort(0)->SetVoltage_V(3.3); + pcu_->GetPowerPort(1)->SetVoltage_V(3.3); + pcu_->GetPowerPort(2)->SetVoltage_V(3.3); /** Examples **/ From 60a0f3722825ab1ccc61c0b912a59f59a6bb485a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:33:57 +0100 Subject: [PATCH 0766/1086] Fix private variables --- src/components/ports/uart_port.cpp | 16 ++++++++-------- src/components/ports/uart_port.hpp | 4 ++-- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index 25c670caf..5ef1acfee 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -10,19 +10,19 @@ SCIPort::SCIPort() : SCIPort(kDefaultBufferSize, kDefaultBufferSize) {} SCIPort::SCIPort(int rx_buffer_size, int tx_buffer_size) { if (rx_buffer_size <= 0) rx_buffer_size = kDefaultBufferSize; if (tx_buffer_size <= 0) tx_buffer_size = kDefaultBufferSize; - rxb_ = new RingBuffer(rx_buffer_size); - txb_ = new RingBuffer(tx_buffer_size); + rx_buffer_ = new RingBuffer(rx_buffer_size); + tx_buffer_ = new RingBuffer(tx_buffer_size); } SCIPort::~SCIPort() { - delete rxb_; - delete txb_; + delete rx_buffer_; + delete tx_buffer_; } -int SCIPort::WriteTx(unsigned char* buffer, int offset, int data_length) { return txb_->Write(buffer, offset, data_length); } +int SCIPort::WriteTx(unsigned char* buffer, int offset, int data_length) { return tx_buffer_->Write(buffer, offset, data_length); } -int SCIPort::WriteRx(unsigned char* buffer, int offset, int data_length) { return rxb_->Write(buffer, offset, data_length); } +int SCIPort::WriteRx(unsigned char* buffer, int offset, int data_length) { return rx_buffer_->Write(buffer, offset, data_length); } -int SCIPort::ReadTx(unsigned char* buffer, int offset, int data_length) { return txb_->Read(buffer, offset, data_length); } +int SCIPort::ReadTx(unsigned char* buffer, int offset, int data_length) { return tx_buffer_->Read(buffer, offset, data_length); } -int SCIPort::ReadRx(unsigned char* buffer, int offset, int data_length) { return rxb_->Read(buffer, offset, data_length); } \ No newline at end of file +int SCIPort::ReadRx(unsigned char* buffer, int offset, int data_length) { return rx_buffer_->Read(buffer, offset, data_length); } \ No newline at end of file diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 8b5883704..f2d38cf4b 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -75,8 +75,8 @@ class SCIPort { private: const static int kDefaultBufferSize = 1024; //!< Default buffer size - RingBuffer* rxb_; //!< Receive buffer (Component -> OBC) - RingBuffer* txb_; //!< Transmit buffer (OBC -> Component) + RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OBC) + RingBuffer* tx_buffer_; //!< Transmit buffer (OBC -> Component) }; #endif // S2E_COMPONENTS_PORTS_UART_PORT_HPP_ From 737970b4fe10b8401d583b8967c307f2387de23b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:47:48 +0100 Subject: [PATCH 0767/1086] Add const and unsigned to function arguments --- src/components/ports/uart_port.cpp | 28 ++++++++++++++++++--------- src/components/ports/uart_port.hpp | 12 ++++++------ src/library/utilities/ring_buffer.cpp | 14 +++++++------- src/library/utilities/ring_buffer.hpp | 12 ++++++------ 4 files changed, 38 insertions(+), 28 deletions(-) diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index 5ef1acfee..61a18319c 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -7,11 +7,13 @@ SCIPort::SCIPort() : SCIPort(kDefaultBufferSize, kDefaultBufferSize) {} -SCIPort::SCIPort(int rx_buffer_size, int tx_buffer_size) { - if (rx_buffer_size <= 0) rx_buffer_size = kDefaultBufferSize; - if (tx_buffer_size <= 0) tx_buffer_size = kDefaultBufferSize; - rx_buffer_ = new RingBuffer(rx_buffer_size); - tx_buffer_ = new RingBuffer(tx_buffer_size); +SCIPort::SCIPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size) { + unsigned int checked_rx_buffer_size = rx_buffer_size; + unsigned int checked_tx_buffer_size = tx_buffer_size; + if (rx_buffer_size <= 0) checked_rx_buffer_size = kDefaultBufferSize; + if (tx_buffer_size <= 0) checked_tx_buffer_size = kDefaultBufferSize; + rx_buffer_ = new RingBuffer(checked_rx_buffer_size); + tx_buffer_ = new RingBuffer(checked_tx_buffer_size); } SCIPort::~SCIPort() { @@ -19,10 +21,18 @@ SCIPort::~SCIPort() { delete tx_buffer_; } -int SCIPort::WriteTx(unsigned char* buffer, int offset, int data_length) { return tx_buffer_->Write(buffer, offset, data_length); } +int SCIPort::WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { + return tx_buffer_->Write(buffer, offset, data_length); +} -int SCIPort::WriteRx(unsigned char* buffer, int offset, int data_length) { return rx_buffer_->Write(buffer, offset, data_length); } +int SCIPort::WriteRx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { + return rx_buffer_->Write(buffer, offset, data_length); +} -int SCIPort::ReadTx(unsigned char* buffer, int offset, int data_length) { return tx_buffer_->Read(buffer, offset, data_length); } +int SCIPort::ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { + return tx_buffer_->Read(buffer, offset, data_length); +} -int SCIPort::ReadRx(unsigned char* buffer, int offset, int data_length) { return rx_buffer_->Read(buffer, offset, data_length); } \ No newline at end of file +int SCIPort::ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { + return rx_buffer_->Read(buffer, offset, data_length); +} \ No newline at end of file diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index f2d38cf4b..a0a6d5c1e 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -27,7 +27,7 @@ class SCIPort { * @param [in] rx_buffer_size: RX(Component -> OBC) buffer size * @param [in] tx_buffer_size: TX(OBC -> Component) buffer size */ - SCIPort(int rx_buffer_size, int tx_buffer_size); + SCIPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size); /** * @fn ~SCIPort * @brief Destructor @@ -42,7 +42,7 @@ class SCIPort { * @param [in] data_length: Length of the data to write * @return Number of written byte */ - int WriteTx(unsigned char* buffer, int offset, int data_length); + int WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn WriteRx * @brief Write data to the RX buffer from Component to OBC @@ -51,7 +51,7 @@ class SCIPort { * @param [in] data_length: Length of the data to write * @return Number of written byte */ - int WriteRx(unsigned char* buffer, int offset, int data_length); + int WriteRx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn ReadTx @@ -61,7 +61,7 @@ class SCIPort { * @param [in] data_length: Length of the data to read * @return Number of read byte */ - int ReadTx(unsigned char* buffer, int offset, int data_length); + int ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn ReadRx * @brief Read data from the TX buffer by OBC @@ -70,10 +70,10 @@ class SCIPort { * @param [in] data_length: Length of the data to read * @return Number of read byte */ - int ReadRx(unsigned char* buffer, int offset, int data_length); + int ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length); private: - const static int kDefaultBufferSize = 1024; //!< Default buffer size + const static unsigned int kDefaultBufferSize = 1024; //!< Default buffer size RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OBC) RingBuffer* tx_buffer_; //!< Transmit buffer (OBC -> Component) diff --git a/src/library/utilities/ring_buffer.cpp b/src/library/utilities/ring_buffer.cpp index da6721477..d89f10204 100644 --- a/src/library/utilities/ring_buffer.cpp +++ b/src/library/utilities/ring_buffer.cpp @@ -18,10 +18,10 @@ RingBuffer::RingBuffer(int buffer_size) : buffer_size_(buffer_size) { RingBuffer::~RingBuffer() { delete[] buffer_; } -int RingBuffer::Write(byte* buffer, int offset, int data_length) { - int write_count = 0; +int RingBuffer::Write(const byte* buffer, const unsigned int offset, const unsigned int data_length) { + unsigned int write_count = 0; while (write_count != data_length) { - int write_len = std::min(buffer_size_ - write_pointer_, data_length - write_count); + unsigned int write_len = std::min(buffer_size_ - write_pointer_, data_length - write_count); memcpy(&buffer_[write_pointer_], &buffer[offset + write_count], write_len); write_pointer_ = (write_pointer_ + write_len == buffer_size_) ? 0 : write_pointer_ + write_len; write_count += write_len; @@ -30,13 +30,13 @@ int RingBuffer::Write(byte* buffer, int offset, int data_length) { return write_count; } -int RingBuffer::Read(byte* buffer, int offset, int data_length) { - int read_count = 0; +int RingBuffer::Read(byte* buffer, const unsigned int offset, const unsigned int data_length) { + unsigned int read_count = 0; // There are four behaviors depending on whether the RP overtakes the WP, or // whether all of the RP to the WP are requested by data_length. while (read_count != data_length && write_pointer_ != read_pointer_) { - int read_len = (write_pointer_ > read_pointer_) ? std::min(write_pointer_ - read_pointer_, data_length - read_count) - : std::min(buffer_size_ - read_pointer_, data_length - read_count); + unsigned int read_len = (write_pointer_ > read_pointer_) ? std::min(write_pointer_ - read_pointer_, data_length - read_count) + : std::min(buffer_size_ - read_pointer_, data_length - read_count); memcpy(&buffer[offset + read_count], &buffer_[read_pointer_], read_len); read_pointer_ = (read_pointer_ + read_len == buffer_size_) ? 0 : read_pointer_ + read_len; read_count += read_len; diff --git a/src/library/utilities/ring_buffer.hpp b/src/library/utilities/ring_buffer.hpp index 55d6fddce..3e133de26 100644 --- a/src/library/utilities/ring_buffer.hpp +++ b/src/library/utilities/ring_buffer.hpp @@ -34,7 +34,7 @@ class RingBuffer { * @param [in] data_length: Data length for buffer * @return Number of bytes written */ - int Write(byte* buffer, int offset, int data_length); + int Write(const byte* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn Read * @brief Read data at the read pointer of the ring buffer and store the data to the buffer[offset] to buffer[offset + data_length] @@ -43,13 +43,13 @@ class RingBuffer { * @param [in] data_length: Data length for buffer * @return Number of bytes read */ - int Read(byte* buffer, int offset, int data_length); + int Read(byte* buffer, const unsigned int offset, const unsigned int data_length); private: - int buffer_size_; //!< Buffer size - byte* buffer_; //!< Buffer - int read_pointer_; //!< Read pointer - int write_pointer_; //!< Write pointer + unsigned int buffer_size_; //!< Buffer size + byte* buffer_; //!< Buffer + unsigned int read_pointer_; //!< Read pointer + unsigned int write_pointer_; //!< Write pointer }; #endif // S2E_LIBRARY_UTILITIES_RING_BUFFER_HPP_ From 2f0f09092bd5c0159ee3696a6a66cd9529cbd50f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:48:48 +0100 Subject: [PATCH 0768/1086] Rename SCIPort to UartPort --- src/components/ports/uart_port.cpp | 14 +++++++------- src/components/ports/uart_port.hpp | 16 ++++++++-------- src/components/real/cdh/on_board_computer.cpp | 12 ++++++------ src/components/real/cdh/on_board_computer.hpp | 2 +- .../real/cdh/on_board_computer_with_c2a.cpp | 14 +++++++------- .../real/cdh/on_board_computer_with_c2a.hpp | 2 +- 6 files changed, 30 insertions(+), 30 deletions(-) diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index 61a18319c..07eef6358 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -5,9 +5,9 @@ #include "uart_port.hpp" -SCIPort::SCIPort() : SCIPort(kDefaultBufferSize, kDefaultBufferSize) {} +UartPort::UartPort() : UartPort(kDefaultBufferSize, kDefaultBufferSize) {} -SCIPort::SCIPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size) { +UartPort::UartPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size) { unsigned int checked_rx_buffer_size = rx_buffer_size; unsigned int checked_tx_buffer_size = tx_buffer_size; if (rx_buffer_size <= 0) checked_rx_buffer_size = kDefaultBufferSize; @@ -16,23 +16,23 @@ SCIPort::SCIPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer tx_buffer_ = new RingBuffer(checked_tx_buffer_size); } -SCIPort::~SCIPort() { +UartPort::~UartPort() { delete rx_buffer_; delete tx_buffer_; } -int SCIPort::WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { +int UartPort::WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { return tx_buffer_->Write(buffer, offset, data_length); } -int SCIPort::WriteRx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { +int UartPort::WriteRx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { return rx_buffer_->Write(buffer, offset, data_length); } -int SCIPort::ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { +int UartPort::ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { return tx_buffer_->Read(buffer, offset, data_length); } -int SCIPort::ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { +int UartPort::ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { return rx_buffer_->Read(buffer, offset, data_length); } \ No newline at end of file diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index a0a6d5c1e..a0f18518e 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -9,30 +9,30 @@ #include /** - * @class SCIPort + * @class UartPort * @brief Class to emulate SCI(Serial Communication Interface) communication port * @details Compatible with anything that performs data communication (UART, I2C, SPI). * The distinction of the area should be done where the upper port ID is assigned. */ -class SCIPort { +class UartPort { public: /** - * @fn SCIPort + * @fn UartPort * @brief Default Constructor. Initialized as default settings. */ - SCIPort(); + UartPort(); /** - * @fn SCIPort + * @fn UartPort * @brief Constructor * @param [in] rx_buffer_size: RX(Component -> OBC) buffer size * @param [in] tx_buffer_size: TX(OBC -> Component) buffer size */ - SCIPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size); + UartPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size); /** - * @fn ~SCIPort + * @fn ~UartPort * @brief Destructor */ - ~SCIPort(); + ~UartPort(); /** * @fn WriteTx diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index f8c555719..bd111f218 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -26,7 +26,7 @@ int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { // Port already used return -1; } - com_ports_[port_id] = new SCIPort(tx_buffer_size, rx_buffer_size); + com_ports_[port_id] = new UartPort(tx_buffer_size, rx_buffer_size); return 0; } @@ -35,32 +35,32 @@ int OBC::CloseComPort(int port_id) { // Port not used if (com_ports_[port_id] == nullptr) return -1; - SCIPort* port = com_ports_.at(port_id); + UartPort* port = com_ports_.at(port_id); delete port; com_ports_.erase(port_id); return 0; } int OBC::SendFromObc(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_[port_id]; + UartPort* port = com_ports_[port_id]; if (port == nullptr) return -1; return port->WriteTx(buffer, offset, count); } int OBC::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_[port_id]; + UartPort* port = com_ports_[port_id]; if (port == nullptr) return -1; return port->ReadTx(buffer, offset, count); } int OBC::SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_[port_id]; + UartPort* port = com_ports_[port_id]; if (port == nullptr) return -1; return port->WriteRx(buffer, offset, count); } int OBC::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_[port_id]; + UartPort* port = com_ports_[port_id]; if (port == nullptr) return -1; return port->ReadRx(buffer, offset, count); } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index d35316c2b..7192d2ae7 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -201,7 +201,7 @@ class OBC : public Component { virtual void MainRoutine(int count); private: - std::map com_ports_; //!< UART ports + std::map com_ports_; //!< UART ports std::map i2c_com_ports_; //!< I2C ports std::map gpio_ports_; //!< GPIO ports }; diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index 0c158ece2..907e91128 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -12,7 +12,7 @@ #include "src_core/c2a_core_main.h" #endif -std::map OBC_C2A::com_ports_c2a_; +std::map OBC_C2A::com_ports_c2a_; std::map OBC_C2A::i2c_com_ports_c2a_; std::map OBC_C2A::gpio_ports_c2a_; @@ -66,7 +66,7 @@ int OBC_C2A::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) // Port already used return -1; } - com_ports_c2a_[port_id] = new SCIPort(tx_buffer_size, rx_buffer_size); + com_ports_c2a_[port_id] = new UartPort(tx_buffer_size, rx_buffer_size); return 0; } @@ -75,7 +75,7 @@ int OBC_C2A::CloseComPort(int port_id) { // Port not used if (com_ports_c2a_[port_id] == nullptr) return -1; - SCIPort* port = com_ports_c2a_.at(port_id); + UartPort* port = com_ports_c2a_.at(port_id); delete port; com_ports_c2a_.erase(port_id); return 0; @@ -86,13 +86,13 @@ int OBC_C2A::SendFromObc(int port_id, unsigned char* buffer, int offset, int cou } int OBC_C2A::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_c2a_[port_id]; + UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->ReadTx(buffer, offset, count); } int OBC_C2A::SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_c2a_[port_id]; + UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->WriteRx(buffer, offset, count); } @@ -103,12 +103,12 @@ int OBC_C2A::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int c // Static functions int OBC_C2A::SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_c2a_[port_id]; + UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->WriteTx(buffer, offset, count); } int OBC_C2A::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int count) { - SCIPort* port = com_ports_c2a_[port_id]; + UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->ReadRx(buffer, offset, count); } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 62b39c4f7..61b51b801 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -265,7 +265,7 @@ class OBC_C2A : public OBC { */ void Initialize(); - static std::map com_ports_c2a_; //!< UART ports + static std::map com_ports_c2a_; //!< UART ports static std::map i2c_com_ports_c2a_; //!< I2C ports static std::map gpio_ports_c2a_; //!< GPIO ports }; From 3df01b47550c261d662bd0d89cace79a4d190f4d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 11:49:58 +0100 Subject: [PATCH 0769/1086] Fix comments --- src/components/ports/uart_port.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index a0f18518e..51598aec2 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -10,9 +10,8 @@ /** * @class UartPort - * @brief Class to emulate SCI(Serial Communication Interface) communication port - * @details Compatible with anything that performs data communication (UART, I2C, SPI). - * The distinction of the area should be done where the upper port ID is assigned. + * @brief Class to emulate UART communication port + * @details The distinction of the area should be done where the upper port ID is assigned. */ class UartPort { public: From 9d4cb0228014d33b7aa9ce630f67c108f0adcf44 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 12:31:29 +0100 Subject: [PATCH 0770/1086] Fix function argument names --- .../examples/example_change_structure.cpp | 3 ++- .../examples/example_change_structure.hpp | 4 ++-- .../examples/example_i2c_controller_for_hils.cpp | 4 ++-- .../examples/example_i2c_controller_for_hils.hpp | 4 ++-- .../examples/example_i2c_target_for_hils.cpp | 7 ++++--- .../examples/example_i2c_target_for_hils.hpp | 4 ++-- .../example_serial_communication_for_hils.cpp | 4 ++-- .../example_serial_communication_for_hils.hpp | 4 ++-- .../example_serial_communication_with_obc.cpp | 8 ++++---- .../example_serial_communication_with_obc.hpp | 8 ++++---- src/components/ideal/force_generator.cpp | 4 ++-- src/components/ideal/force_generator.hpp | 4 ++-- src/components/ideal/initialize_force_generator.cpp | 4 ++-- src/components/ideal/initialize_force_generator.hpp | 4 ++-- .../ideal/initialize_torque_generator.cpp | 5 +++-- .../ideal/initialize_torque_generator.hpp | 4 ++-- src/components/ideal/torque_generator.cpp | 4 ++-- src/components/ideal/torque_generator.hpp | 4 ++-- src/components/real/aocs/gnss_receiver.cpp | 8 ++++---- src/components/real/aocs/gnss_receiver.hpp | 8 ++++---- src/components/real/aocs/gyro_sensor.cpp | 8 ++++---- src/components/real/aocs/gyro_sensor.hpp | 8 ++++---- .../real/aocs/initialize_gnss_receiver.cpp | 8 ++++---- .../real/aocs/initialize_gnss_receiver.hpp | 8 ++++---- src/components/real/aocs/initialize_gyro_sensor.cpp | 8 ++++---- src/components/real/aocs/initialize_gyro_sensor.hpp | 8 ++++---- .../real/aocs/initialize_magnetometer.cpp | 8 ++++---- .../real/aocs/initialize_magnetometer.hpp | 8 ++++---- .../real/aocs/initialize_magnetorquer.cpp | 8 ++++---- .../real/aocs/initialize_magnetorquer.hpp | 8 ++++---- .../real/aocs/initialize_reaction_wheel.cpp | 8 ++++---- .../real/aocs/initialize_reaction_wheel.hpp | 8 ++++---- src/components/real/aocs/initialize_star_sensor.cpp | 8 ++++---- src/components/real/aocs/initialize_star_sensor.hpp | 8 ++++---- src/components/real/aocs/initialize_sun_sensor.cpp | 10 +++++----- src/components/real/aocs/initialize_sun_sensor.hpp | 8 ++++---- src/components/real/aocs/magnetometer.cpp | 8 ++++---- src/components/real/aocs/magnetometer.hpp | 8 ++++---- src/components/real/aocs/magnetorquer.cpp | 8 ++++---- src/components/real/aocs/magnetorquer.hpp | 8 ++++---- src/components/real/aocs/reaction_wheel.cpp | 8 ++++---- src/components/real/aocs/reaction_wheel.hpp | 8 ++++---- src/components/real/aocs/star_sensor.cpp | 8 ++++---- src/components/real/aocs/star_sensor.hpp | 8 ++++---- src/components/real/aocs/sun_sensor.cpp | 8 ++++---- src/components/real/aocs/sun_sensor.hpp | 8 ++++---- src/components/real/cdh/on_board_computer.cpp | 8 ++++---- src/components/real/cdh/on_board_computer.hpp | 12 ++++++------ .../real/cdh/on_board_computer_with_c2a.cpp | 8 ++++---- .../real/cdh/on_board_computer_with_c2a.hpp | 12 ++++++------ .../real/mission/initialize_telescope.cpp | 6 +++--- .../real/mission/initialize_telescope.hpp | 6 +++--- src/components/real/mission/telescope.cpp | 4 ++-- src/components/real/mission/telescope.hpp | 2 +- src/components/real/power/battery.cpp | 8 ++++---- src/components/real/power/battery.hpp | 8 ++++---- src/components/real/power/initialize_battery.cpp | 4 ++-- src/components/real/power/initialize_battery.hpp | 4 ++-- .../real/power/initialize_pcu_initial_study.cpp | 4 ++-- .../real/power/initialize_pcu_initial_study.hpp | 4 ++-- .../real/power/initialize_solar_array_panel.cpp | 13 +++++++------ .../real/power/initialize_solar_array_panel.hpp | 9 +++++---- src/components/real/power/pcu_initial_study.cpp | 9 +++++---- src/components/real/power/pcu_initial_study.hpp | 8 ++++---- src/components/real/power/power_control_unit.cpp | 4 ++-- src/components/real/power/power_control_unit.hpp | 8 ++++---- src/components/real/power/solar_array_panel.cpp | 12 ++++++------ src/components/real/power/solar_array_panel.hpp | 12 ++++++------ .../real/propulsion/initialize_simple_thruster.cpp | 9 +++++---- .../real/propulsion/initialize_simple_thruster.hpp | 8 ++++---- src/components/real/propulsion/simple_thruster.cpp | 12 ++++++------ src/components/real/propulsion/simple_thruster.hpp | 8 ++++---- 72 files changed, 259 insertions(+), 252 deletions(-) diff --git a/src/components/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp index 5bfc7a476..714524a12 100644 --- a/src/components/examples/example_change_structure.cpp +++ b/src/components/examples/example_change_structure.cpp @@ -5,7 +5,8 @@ #include "example_change_structure.hpp" -ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure) : Component(1, clock_gen), structure_(structure) {} +ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_generator, Structure* structure) + : Component(1, clock_generator), structure_(structure) {} ExampleChangeStructure::~ExampleChangeStructure() {} diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index a5d27626c..16fc5cae0 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -20,10 +20,10 @@ class ExampleChangeStructure : public Component, public ILoggable { /** * @fn ExampleChangeStructure * @brief Constructor with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] structure: Structure information */ - ExampleChangeStructure(ClockGenerator* clock_gen, Structure* structure); + ExampleChangeStructure(ClockGenerator* clock_generator, Structure* structure); /** * @fn ~ChangeStructure * @brief Destructor diff --git a/src/components/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp index 8e3bb3e94..296bd9040 100644 --- a/src/components/examples/example_i2c_controller_for_hils.cpp +++ b/src/components/examples/example_i2c_controller_for_hils.cpp @@ -4,10 +4,10 @@ */ #include "example_i2c_controller_for_hils.hpp" -ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, +ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_generator, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager) - : Component(prescaler, clock_gen), I2cController(hils_port_id, baud_rate, tx_buffer_size, rx_buffer_size, hils_port_manager) {} + : Component(prescaler, clock_generator), I2cController(hils_port_id, baud_rate, tx_buffer_size, rx_buffer_size, hils_port_manager) {} ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index 1363a9e82..af7e2b2e5 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -24,14 +24,14 @@ class ExampleI2cControllerForHils : public Component, public I2cController { * @fn ExampleI2cControllerForHils * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] tx_buffer_size: TX (Controller to Target) buffer size * @param [in] rx_buffer_size: RX (Target to Controller) buffer size * @param [in] hils_port_manager: HILS port manager */ - ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_gen, const unsigned int hils_port_id, const unsigned int baud_rate, + ExampleI2cControllerForHils(const int prescaler, ClockGenerator* clock_generator, const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cControllerForHils diff --git a/src/components/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp index e2f0bab0e..50219144a 100644 --- a/src/components/examples/example_i2c_target_for_hils.cpp +++ b/src/components/examples/example_i2c_target_for_hils.cpp @@ -5,9 +5,10 @@ #include "example_i2c_target_for_hils.hpp" -ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, - OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) - : Component(prescaler, clock_gen), I2cTargetCommunicationWithObc(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} +ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, + unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, + HilsPortManager* hils_port_manager) + : Component(prescaler, clock_generator), I2cTargetCommunicationWithObc(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} ExampleI2cTargetForHils::~ExampleI2cTargetForHils() {} diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 1cd7ace2e..ced67e411 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -25,14 +25,14 @@ class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationW * @fn ExampleI2cTargetForHils * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sils_port_id: Port ID for communication line b/w OBC * @param [in] i2c_address: I2C address of the target device (This value should be compatible with MFT200XD's setting) * @param [in] obc: The communication target OBC * @param [in] hils_port_id: ID of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_gen, const int sils_port_id, unsigned char i2c_address, OBC* obc, + ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cTargetForHils diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index b6c32f5e4..2985ee22a 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -6,10 +6,10 @@ #include -ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, +ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id) - : Component(300, clock_gen), UartCommunicationWithObc(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} + : Component(300, clock_generator), UartCommunicationWithObc(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} ExampleSerialCommunicationForHils::~ExampleSerialCommunicationForHils() {} diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index e19053c70..ce8fe9915 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -26,7 +26,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @fn ExampleSerialCommunicationForHils * @brief Constructor * @note prescaler is set as 300. - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sils_port_id: Port ID for communication line b/w OBC * @param [in] obc: The communication target OBC * @param [in] hils_port_id: ID of HILS communication port @@ -34,7 +34,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @param [in] hils_port_manager: HILS port manager * @param [in] mode_id: Mode ID to select sender(0) or responder(1) */ - ExampleSerialCommunicationForHils(ClockGenerator* clock_gen, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, + ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id); /** * @fn ~ExampleSerialCommunicationForHils diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index f232851c3..590d01598 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -7,12 +7,12 @@ #include -ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc) - : Component(1000, clock_gen), UartCommunicationWithObc(port_id, obc) { +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OBC* obc) + : Component(1000, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } -ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc) - : Component(prescaler, clock_gen), UartCommunicationWithObc(port_id, obc) { +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OBC* obc) + : Component(prescaler, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 165a5798e..a54121396 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -31,20 +31,20 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @fn ExampleSerialCommunicationWithObc * @brief Constructor without prescaler * @note The prescaler is set as 1000 - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] obc: The communication target OBC */ - ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OBC* obc); /** * @fn ExampleSerialCommunicationWithObc * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] port_id: Port ID for communication line b/w OBC * @param [in] prescaler: Frequency scale factor for update * @param [in] obc: The communication target OBC */ - ExampleSerialCommunicationWithObc(ClockGenerator* clock_gen, int port_id, int prescaler, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OBC* obc); /** * @fn ~SerialCommunicationWithObc * @brief Destructor diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 5c5da2d43..1224ae110 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -8,9 +8,9 @@ #include // Constructor -ForceGenerator::ForceGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_N, +ForceGenerator::ForceGenerator(const int prescaler, ClockGenerator* clock_generator, const double magnitude_error_standard_deviation_N, const double direction_error_standard_deviation_rad, const Dynamics* dynamics) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), magnitude_noise_(0.0, magnitude_error_standard_deviation_N), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { diff --git a/src/components/ideal/force_generator.hpp b/src/components/ideal/force_generator.hpp index 0c1e3b9a1..d4fdd8ac3 100644 --- a/src/components/ideal/force_generator.hpp +++ b/src/components/ideal/force_generator.hpp @@ -22,12 +22,12 @@ class ForceGenerator : public Component, public ILoggable { * @fn ForceGenerator * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] magnitude_error_standard_deviation_N: Standard deviation of magnitude error [N] * @param [in] direction_error_standard_deviation_rad: Standard deviation of direction error [rad] * @param [in] dynamics: Dynamics information */ - ForceGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_N, + ForceGenerator(const int prescaler, ClockGenerator* clock_generator, const double magnitude_error_standard_deviation_N, const double direction_error_standard_deviation_rad, const Dynamics* dynamics); /** * @fn ~ForceGenerator diff --git a/src/components/ideal/initialize_force_generator.cpp b/src/components/ideal/initialize_force_generator.cpp index 1e7df7cd9..4a26019a0 100644 --- a/src/components/ideal/initialize_force_generator.cpp +++ b/src/components/ideal/initialize_force_generator.cpp @@ -6,7 +6,7 @@ #include -ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { +ForceGenerator InitializeForceGenerator(ClockGenerator* clock_generator, const std::string file_name, const Dynamics* dynamics) { // General IniAccess ini_file(file_name); @@ -19,7 +19,7 @@ ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::st double force_magnitude_standard_deviation_N = ini_file.ReadDouble(section, "force_magnitude_standard_deviation_N"); double force_direction_standard_deviation_deg = ini_file.ReadDouble(section, "force_direction_standard_deviation_deg"); double force_direction_standard_deviation_rad = libra::deg_to_rad * force_direction_standard_deviation_deg; - ForceGenerator force_generator(prescaler, clock_gen, force_magnitude_standard_deviation_N, force_direction_standard_deviation_rad, dynamics); + ForceGenerator force_generator(prescaler, clock_generator, force_magnitude_standard_deviation_N, force_direction_standard_deviation_rad, dynamics); return force_generator; } diff --git a/src/components/ideal/initialize_force_generator.hpp b/src/components/ideal/initialize_force_generator.hpp index 49d72f83d..d853a6cf4 100644 --- a/src/components/ideal/initialize_force_generator.hpp +++ b/src/components/ideal/initialize_force_generator.hpp @@ -11,10 +11,10 @@ /** * @fn InitializeForceGenerator * @brief Initialize function for ForceGenerator - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] file_name: Path to initialize file * @param [in] dynamics: Dynamics information */ -ForceGenerator InitializeForceGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); +ForceGenerator InitializeForceGenerator(ClockGenerator* clock_generator, const std::string file_name, const Dynamics* dynamics); #endif // S2E_COMPONENTS_IDEAL_INITIALIZE_FORCE_GENERATOR_HPP_ diff --git a/src/components/ideal/initialize_torque_generator.cpp b/src/components/ideal/initialize_torque_generator.cpp index d6798da4c..b0df1771a 100644 --- a/src/components/ideal/initialize_torque_generator.cpp +++ b/src/components/ideal/initialize_torque_generator.cpp @@ -6,7 +6,7 @@ #include -TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics) { +TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_generator, const std::string file_name, const Dynamics* dynamics) { // General IniAccess ini_file(file_name); @@ -19,7 +19,8 @@ TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std:: double torque_magnitude_standard_deviation_Nm = ini_file.ReadDouble(section, "torque_magnitude_standard_deviation_Nm"); double torque_direction_standard_deviation_deg = ini_file.ReadDouble(section, "torque_direction_standard_deviation_deg"); double torque_direction_standard_deviation_rad = libra::deg_to_rad * torque_direction_standard_deviation_deg; - TorqueGenerator torque_generator(prescaler, clock_gen, torque_magnitude_standard_deviation_Nm, torque_direction_standard_deviation_rad, dynamics); + TorqueGenerator torque_generator(prescaler, clock_generator, torque_magnitude_standard_deviation_Nm, torque_direction_standard_deviation_rad, + dynamics); return torque_generator; } diff --git a/src/components/ideal/initialize_torque_generator.hpp b/src/components/ideal/initialize_torque_generator.hpp index 562f4694b..0484d0a1d 100644 --- a/src/components/ideal/initialize_torque_generator.hpp +++ b/src/components/ideal/initialize_torque_generator.hpp @@ -11,10 +11,10 @@ /** * @fn InitializeTorqueGenerator * @brief Initialize function for TorqueGenerator - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] file_name: Path to initialize file * @param [in] dynamics: Dynamics information */ -TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_gen, const std::string file_name, const Dynamics* dynamics); +TorqueGenerator InitializeTorqueGenerator(ClockGenerator* clock_generator, const std::string file_name, const Dynamics* dynamics); #endif // S2E_COMPONENTS_IDEAL_INITIALIZE_TORQUE_GENERATOR_HPP_ diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 94cb026f7..43a616b03 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -8,9 +8,9 @@ #include // Constructor -TorqueGenerator::TorqueGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_Nm, +TorqueGenerator::TorqueGenerator(const int prescaler, ClockGenerator* clock_generator, const double magnitude_error_standard_deviation_Nm, const double direction_error_standard_deviation_rad, const Dynamics* dynamics) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), magnitude_noise_(0.0, magnitude_error_standard_deviation_Nm), direction_error_standard_deviation_rad_(direction_error_standard_deviation_rad), dynamics_(dynamics) { diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index 4ceee221e..bba4a2a0b 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -22,12 +22,12 @@ class TorqueGenerator : public Component, public ILoggable { * @fn TorqueGenerator * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] magnitude_error_standard_deviation_Nm: Standard deviation of magnitude error [Nm] * @param [in] direction_error_standard_deviation_rad: Standard deviation of direction error [rad] * @param [in] dynamics: Dynamics information */ - TorqueGenerator(const int prescaler, ClockGenerator* clock_gen, const double magnitude_error_standard_deviation_Nm, + TorqueGenerator(const int prescaler, ClockGenerator* clock_generator, const double magnitude_error_standard_deviation_Nm, const double direction_error_standard_deviation_rad, const Dynamics* dynamics); /** * @fn ~TorqueGenerator diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 0da9a5282..7b7c66f14 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -9,10 +9,10 @@ #include #include -GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, +GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), ch_max_(ch_max), antenna_position_b_(ant_pos_b), @@ -26,11 +26,11 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const dynamics_(dynamics), gnss_satellites_(gnss_satellites), simtime_(simtime) {} -GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const std::string gnss_id, +GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) - : Component(prescaler, clock_gen, power_port), + : Component(prescaler, clock_generator, power_port), id_(id), ch_max_(ch_max), antenna_position_b_(ant_pos_b), diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 294e7ad2e..c40d921e0 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -47,7 +47,7 @@ class GNSSReceiver : public Component, public ILoggable { * @fn GNSSReceiver * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels * @param [in] antenna_model: Antenna model @@ -59,14 +59,14 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_satellites: GNSS Satellites information * @param [in] simtime: Simulation time information */ - GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, const int id, const std::string gnss_id, const int ch_max, + GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); /** * @fn GNSSReceiver * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels @@ -79,7 +79,7 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_satellites: GNSS Satellites information * @param [in] simtime: Simulation time information */ - GNSSReceiver(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, + GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index f36bdc76c..ff41bb730 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,13 +5,13 @@ #include "gyro_sensor.hpp" -Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, +Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_gen), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} -Gyro::Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, +Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_gen, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} Gyro::~Gyro() {} diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index 4c5bcac89..fe62b8e58 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -25,26 +25,26 @@ class Gyro : public Component, public Sensor, public ILoggable { * @fn Gyro * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics); /** * @fn Gyro * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const Dynamics* dynamics); /** * @fn ~Gyro diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index a3c15a625..987c0e221 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -49,23 +49,23 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli return gnssreceiver_param; } -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::string fname, const Dynamics* dynamics, +GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); - GNSSReceiver gnss_r(gr_param.prescaler, clock_gen, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, + GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); return gnss_r; } -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, +GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); // PowerPort power_port->InitializeWithInitializeFile(fname); - GNSSReceiver gnss_r(gr_param.prescaler, clock_gen, power_port, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, + GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); return gnss_r; } diff --git a/src/components/real/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp index 71c010a46..284e8a928 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -11,19 +11,19 @@ /** * @fn InitGNSSReceiver * @brief Initialize functions for GNSS Receiver without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information * @param [in] simtime: Simulation time information */ -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::string fname, const Dynamics* dynamics, +GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); /** * @fn InitGNSSReceiver * @brief Initialize functions for GNSS Receiver with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID * @param [in] power_port: Power port * @param [in] fname: Path to the initialize file @@ -31,7 +31,7 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, int id, const std::stri * @param [in] gnss_satellites: GNSS satellites information * @param [in] simtime: Simulation time information */ -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_gen, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, +GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index a7705a5a8..26fe1fdb5 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -8,7 +8,7 @@ #include "../../base/initialize_sensor.hpp" -Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { +Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -22,12 +22,12 @@ Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); - Gyro gyro(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_generator, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } -Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); const char* sensor_name = "GYRO_SENSOR_"; @@ -45,6 +45,6 @@ Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, c // PowerPort power_port->InitializeWithInitializeFile(fname); - Gyro gyro(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, q_b2c, dynamics); return gyro; } diff --git a/src/components/real/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp index 5ac689cbb..56cff2a6b 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -11,24 +11,24 @@ /** * @fn InitGyro * @brief Initialize functions for gyro sensor without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] compo_step_time: Component step time [sec] * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information */ -Gyro InitGyro(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); +Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); /** * @fn InitGyro * @brief Initialize functions for gyro sensor with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] compo_step_time: Component step time [sec] * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information */ -Gyro InitGyro(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index f725b4d84..b7d4feae3 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,7 +7,7 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet) { +MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -22,11 +22,11 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::str // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); - MagSensor magsensor(prescaler, clock_gen, sensor_base, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, q_b2c, magnet); return magsensor; } -MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; @@ -45,6 +45,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int se // PowerPort power_port->InitializeWithInitializeFile(fname); - MagSensor magsensor(prescaler, clock_gen, power_port, sensor_base, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, q_b2c, magnet); return magsensor; } diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 45cf740ee..03648b087 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -11,24 +11,24 @@ /** * @fn InitMagSensor * @brief Initialize functions for magnetometer without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet); +MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet); /** * @fn InitMagSensor * @brief Initialize functions for magnetometer with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index d6b42b4e5..6b8bed5b7 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -6,7 +6,7 @@ #include "library/initialize/initialize_file_access.hpp" -MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, +MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, const GeomagneticField* mag_env) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; @@ -45,12 +45,12 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std: Vector nr_stddev_c; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); - MagTorquer magtorquer(prescaler, clock_gen, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, + MagTorquer magtorquer(prescaler, clock_generator, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); return magtorquer; } -MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, +MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const GeomagneticField* mag_env) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; @@ -92,7 +92,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int // PowerPort power_port->InitializeWithInitializeFile(fname); - MagTorquer magtorquer(prescaler, clock_gen, power_port, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, + MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); return magtorquer; } diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index fcc319d06..40efd3589 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -11,25 +11,25 @@ /** * @fn InitMagTorquer * @brief Initialize functions for magnetometer without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mag_env: Geomegnetic environment */ -MagTorquer InitMagTorquer(ClockGenerator* clock_gen, int actuator_id, const std::string fname, double compo_step_time, +MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, const GeomagneticField* mag_env); /** * @fn InitMagTorquer * @brief Initialize functions for magnetometer with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] actuator_id: Actuator ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mag_env: Geomegnetic environment */ -MagTorquer InitMagTorquer(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, +MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, const GeomagneticField* mag_env); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index cdfc0646f..c51ba0082 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -98,10 +98,10 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double } } // namespace -RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { +RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); @@ -109,13 +109,13 @@ RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file return rwmodel; } -RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, +RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_gen, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); diff --git a/src/components/real/aocs/initialize_reaction_wheel.hpp b/src/components/real/aocs/initialize_reaction_wheel.hpp index f4f035d02..97696aa95 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.hpp +++ b/src/components/real/aocs/initialize_reaction_wheel.hpp @@ -11,24 +11,24 @@ /** * @fn InitRWModel * @brief Initialize functions for reaction wheel without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID * @param [in] file_name: Path to the initialize file * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -RWModel InitRWModel(ClockGenerator* clock_gen, int actuator_id, std::string file_name, double prop_step, double compo_update_step); +RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step); /** * @fn InitRWModel * @brief Initialize functions for reaction wheel with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] actuator_id: Actuator ID * @param [in] file_name: Path to the initialize file * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -RWModel InitRWModel(ClockGenerator* clock_gen, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, +RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, double compo_update_step); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index e328a029f..075dd23ab 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -10,7 +10,7 @@ using namespace std; -STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, +STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; @@ -37,12 +37,12 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const string fname, double double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; - STT stt(prescaler, clock_gen, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, + STT stt(prescaler, clock_generator, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); return stt; } -STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, +STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; @@ -72,7 +72,7 @@ STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, con power_port->InitializeWithInitializeFile(fname); - STT stt(prescaler, clock_gen, power_port, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, + STT stt(prescaler, clock_generator, power_port, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); return stt; } diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index 18e1b99cd..067b8a0e3 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -11,19 +11,19 @@ /** * @fn InitSTT * @brief Initialize functions for STT without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ -STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, +STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env); /** * @fn InitSTT * @brief Initialize functions for STT with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file @@ -31,7 +31,7 @@ STT InitSTT(ClockGenerator* clock_gen, int sensor_id, const std::string fname, d * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ -STT InitSTT(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_env); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index ca09b7a9d..c8aad0b4b 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; @@ -38,12 +38,12 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, int ss_id, std::string file_n double intensity_lower_threshold_percent; intensity_lower_threshold_percent = ss_conf.ReadDouble(Section, "intensity_lower_threshold_percent"); - SunSensor ss(prescaler, clock_gen, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, srp, + SunSensor ss(prescaler, clock_generator, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, srp, local_celes_info); return ss; } -SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss_id, std::string file_name, +SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; @@ -73,7 +73,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int ss power_port->InitializeWithInitializeFile(file_name); - SunSensor ss(prescaler, clock_gen, power_port, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, - srp, local_celes_info); + SunSensor ss(prescaler, clock_generator, power_port, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, + intensity_lower_threshold_percent, srp, local_celes_info); return ss; } diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index ee47f9aa9..ac398a51c 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -11,25 +11,25 @@ /** * @fn InitSunSensor * @brief Initialize functions for sun sensor without power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] srp: Solar radiation pressure environment * @param [in] local_env: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** * @fn InitSunSensor * @brief Initialize functions for sun sensor with power port - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] srp: Solar radiation pressure environment * @param [in] local_env: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_gen, PowerPort* power_port, int sensor_id, const std::string fname, +SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 5d1d5cd24..7ad3a6bc9 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -6,12 +6,12 @@ #include -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_gen), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_gen, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index df08eafaf..457d70ac5 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -25,26 +25,26 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @fn MagSensor * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_gen, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const GeomagneticField* magnet); /** * @fn MagSensor * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, const GeomagneticField* magnet); /** * @fn ~MagSensor diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 38241459f..bbb9ded4c 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -10,11 +10,11 @@ #include #include -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const Quaternion& q_b2c, +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), q_b2c_(q_b2c), q_c2b_(q_b2c_.Conjugate()), @@ -29,11 +29,11 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int } } -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const Quaternion& q_b2c, +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Quaternion& q_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) - : Component(prescaler, clock_gen, power_port), + : Component(prescaler, clock_generator, power_port), id_(id), q_b2c_(q_b2c), q_c2b_(q_b2c_.Conjugate()), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index fd51efa80..1ef457071 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -28,7 +28,7 @@ class MagTorquer : public Component, public ILoggable { * @fn MagTorquer * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id : Actuator ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] scale_facter: Scale factor matrix @@ -41,7 +41,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, + MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); @@ -49,7 +49,7 @@ class MagTorquer : public Component, public ILoggable { * @fn MagTorquer * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id : Actuator ID * @param [in] q_b2c: Quaternion from body frame to component frame @@ -63,7 +63,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, + MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index d83d7ac3b..46cb37385 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -17,13 +17,13 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, const int id, double step_width, double dt_main_routine, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion q_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) - : Component(prescaler, clock_gen, fast_prescaler), + : Component(prescaler, clock_generator, fast_prescaler), id_(id), inertia_(inertia), max_torque_(max_torque), @@ -44,14 +44,14 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, c Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, double step_width, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion q_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) - : Component(prescaler, clock_gen, power_port, fast_prescaler), + : Component(prescaler, clock_generator, power_port, fast_prescaler), id_(id), inertia_(inertia), max_torque_(max_torque), diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 32df88016..0d759c1fe 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -30,7 +30,7 @@ class RWModel : public Component, public ILoggable { * @note TODO: argument is too long * @param [in] prescaler: Frequency scale factor for update * @param [in] fast_prescaler: Frequency scale factor for fast update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] @@ -54,7 +54,7 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, const int id, const double step_width, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -66,7 +66,7 @@ class RWModel : public Component, public ILoggable { * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] fast_prescaler: Frequency scale factor for fast update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] @@ -91,7 +91,7 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_gen, PowerPort *power_port, const int id, const double step_width, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 3b941be23..1cfcc083e 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -15,11 +15,11 @@ using namespace std; using namespace libra; -STT::STT(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, +STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), q_b2c_(q_b2c), rot_(global_randomization.MakeSeed()), @@ -38,11 +38,11 @@ STT::STT(const int prescaler, ClockGenerator* clock_gen, const int id, const lib local_env_(local_env) { Initialize(); } -STT::STT(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, +STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) - : Component(prescaler, clock_gen, power_port), + : Component(prescaler, clock_generator, power_port), id_(id), q_b2c_(q_b2c), rot_(global_randomization.MakeSeed()), diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 13ccafa89..f31f6dcff 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -28,7 +28,7 @@ class STT : public Component, public ILoggable { * @fn STT * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] @@ -43,7 +43,7 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, + STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); @@ -51,7 +51,7 @@ class STT : public Component, public ILoggable { * @fn STT * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame @@ -67,7 +67,7 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, + STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 99f56e39d..ade3471e9 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -13,10 +13,10 @@ using libra::NormalRand; using namespace std; -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), q_b2c_(q_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), @@ -26,11 +26,11 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, const int i Initialize(nr_stddev_c, nr_bias_stddev_c); } -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : Component(prescaler, clock_gen, power_port), + : Component(prescaler, clock_generator, power_port), id_(id), q_b2c_(q_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 4919d7c79..bbc1b6c3e 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -25,7 +25,7 @@ class SunSensor : public Component, public ILoggable { * @fn SunSensor * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] @@ -35,14 +35,14 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_gen, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, + SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** * @fn SunSensor * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Sensor ID * @param [in] q_b2c: Quaternion from body frame to component frame @@ -53,7 +53,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, + SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index bd111f218..1fe82fa09 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -4,12 +4,12 @@ */ #include "on_board_computer.hpp" -OBC::OBC(ClockGenerator* clock_gen) : Component(1, clock_gen) { Initialize(); } +OBC::OBC(ClockGenerator* clock_generator) : Component(1, clock_generator) { Initialize(); } -OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port) : Component(prescaler, clock_gen, power_port) { Initialize(); } +OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port) : Component(prescaler, clock_generator, power_port) { Initialize(); } -OBC::OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption) - : Component(prescaler, clock_gen, power_port) { +OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption) + : Component(prescaler, clock_generator, power_port) { power_port_->SetMinimumVoltage_V(minimum_voltage); power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption); Initialize(); diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 7192d2ae7..123a1de22 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -23,27 +23,27 @@ class OBC : public Component { /** * @fn OBC * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator */ - OBC(ClockGenerator* clock_gen); + OBC(ClockGenerator* clock_generator); /** * @fn OBC * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port */ - OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port); + OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port); /** * @fn OBC * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] minimum_voltage: Minimum voltage [V] * @param [in] assumed_power_consumption: Assumed power consumption [W] */ - OBC(int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption); + OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption); /** * @fn ~OBC * @brief Destructor diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index 907e91128..bb00e729a 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -16,16 +16,16 @@ std::map OBC_C2A::com_ports_c2a_; std::map OBC_C2A::i2c_com_ports_c2a_; std::map OBC_C2A::gpio_ports_c2a_; -OBC_C2A::OBC_C2A(ClockGenerator* clock_gen) : OBC(clock_gen), timing_regulator_(1) { +OBC_C2A::OBC_C2A(ClockGenerator* clock_generator) : OBC(clock_generator), timing_regulator_(1) { // Initialize(); } -OBC_C2A::OBC_C2A(ClockGenerator* clock_gen, int timing_regulator) : OBC(clock_gen), timing_regulator_(timing_regulator) { +OBC_C2A::OBC_C2A(ClockGenerator* clock_generator, int timing_regulator) : OBC(clock_generator), timing_regulator_(timing_regulator) { // Initialize(); } -OBC_C2A::OBC_C2A(int prescaler, ClockGenerator* clock_gen, int timing_regulator, PowerPort* power_port) - : OBC(prescaler, clock_gen, power_port), timing_regulator_(timing_regulator) { +OBC_C2A::OBC_C2A(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port) + : OBC(prescaler, clock_generator, power_port), timing_regulator_(timing_regulator) { // Initialize(); } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 61b51b801..dd3164f39 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -19,25 +19,25 @@ class OBC_C2A : public OBC { /** * @fn OBC_C2A * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator */ - OBC_C2A(ClockGenerator* clock_gen); + OBC_C2A(ClockGenerator* clock_generator); /** * @fn OBC_C2A * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] timing_regulator: Timing regulator to update flight software faster than the component update */ - OBC_C2A(ClockGenerator* clock_gen, int timing_regulator); + OBC_C2A(ClockGenerator* clock_generator, int timing_regulator); /** * @fn OBC_C2A * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] timing_regulator: Timing regulator to update flight software faster than the component update * @param [in] power_port: Power port */ - OBC_C2A(int prescaler, ClockGenerator* clock_gen, int timing_regulator, PowerPort* power_port); + OBC_C2A(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port); /** * @fn ~OBC_C2A * @brief Destructor diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index d57f743df..b5f1b07ba 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -13,7 +13,7 @@ using namespace std; -Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, +Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info) { using libra::pi; @@ -48,7 +48,7 @@ Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const string f int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); - Telescope telescope(clock_gen, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, y_num_of_pix, - x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); + Telescope telescope(clock_generator, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, + y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); return telescope; } diff --git a/src/components/real/mission/initialize_telescope.hpp b/src/components/real/mission/initialize_telescope.hpp index 34696d601..b67694904 100644 --- a/src/components/real/mission/initialize_telescope.hpp +++ b/src/components/real/mission/initialize_telescope.hpp @@ -11,14 +11,14 @@ /* * @fn InitTelescope * @brief Initialize function of Telescope - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to initialize file * @param [in] attitude: Attitude information * @param [in] hipp: Star information by Hipparcos catalogue * @param [in] local_celes_info: Local celestial information */ -Telescope InitTelescope(ClockGenerator* clock_gen, int sensor_id, const std::string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info); +Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const Attitude* attitude, + const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); #endif // S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 9aacc091c..d117eb0d4 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -11,11 +11,11 @@ using namespace std; using namespace libra; -Telescope::Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, +Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info) - : Component(1, clock_gen), + : Component(1, clock_generator), q_b2c_(q_b2c), sun_forbidden_angle_(sun_forbidden_angle), earth_forbidden_angle_(earth_forbidden_angle), diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 9a086e181..32601ca6b 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -30,7 +30,7 @@ struct Star { */ class Telescope : public Component, public ILoggable { public: - Telescope(ClockGenerator* clock_gen, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, + Telescope(ClockGenerator* clock_generator, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 686e6c6f6..75cc66c6d 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -7,10 +7,10 @@ #include -BAT::BAT(const int prescaler, ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, +BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance, double compo_step_time) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_capacity_(cell_capacity), @@ -21,10 +21,10 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_gen, int number_of_series, i bat_resistance_(bat_resistance), compo_step_time_(compo_step_time) {} -BAT::BAT(ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, +BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance) - : Component(10, clock_gen), + : Component(10, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_capacity_(cell_capacity), diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 044f051a2..65ff14764 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -21,7 +21,7 @@ class BAT : public Component, public ILoggable { * @fn BAT * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] number_of_series: Number of series connected cells * @param [in] number_of_parallel: Number of parallel connected cells * @param [in] cell_capacity: Power capacity of a cell [Ah] @@ -32,14 +32,14 @@ class BAT : public Component, public ILoggable { * @param [in] bat_resistance: Battery internal resistance [Ohm] * @param [in] compo_step_time: Component step time [sec] */ - BAT(const int prescaler, ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, + BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance, double compo_step_time); /** * @fn BAT * @brief Constructor without prescaler * @note prescaler is set as 10 - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] number_of_series: Number of series connected cells * @param [in] number_of_parallel: Number of parallel connected cells * @param [in] cell_capacity: Power capacity of a cell [Ah] @@ -50,7 +50,7 @@ class BAT : public Component, public ILoggable { * @param [in] bat_resistance: Battery internal resistance [Ohm] * @param [in] compo_step_time: Component step time [sec] */ - BAT(ClockGenerator* clock_gen, int number_of_series, int number_of_parallel, double cell_capacity, + BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, double bat_resistance); /** diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index d0db603f0..6ffbe404f 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time) { +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string fname, double compo_step_time) { IniAccess bat_conf(fname); const std::string st_bat_id = std::to_string(bat_id); @@ -51,7 +51,7 @@ BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, doub double bat_resistance; bat_resistance = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); - BAT bat(prescaler, clock_gen, number_of_series, number_of_parallel, cell_capacity, cell_discharge_curve_coeffs, initial_dod, cc_charge_c_rate, + BAT bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity, cell_discharge_curve_coeffs, initial_dod, cc_charge_c_rate, cv_charge_voltage, bat_resistance, compo_step_time); return bat; diff --git a/src/components/real/power/initialize_battery.hpp b/src/components/real/power/initialize_battery.hpp index d960be9a9..d4a12f084 100644 --- a/src/components/real/power/initialize_battery.hpp +++ b/src/components/real/power/initialize_battery.hpp @@ -11,11 +11,11 @@ /* * @fn InitBAT * @brief Initialize function of BAT - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] bat_id: Battery ID * @param [in] fname: Path to initialize file * @param [in] compo_step_time: Component step time [sec] */ -BAT InitBAT(ClockGenerator* clock_gen, int bat_id, const std::string fname, double compo_step_time); +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string fname, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 1bda59acb..065fed39a 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -11,7 +11,7 @@ #include "library/initialize/initialize_file_access.hpp" -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time) { IniAccess pcu_conf(fname); @@ -24,7 +24,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, con int prescaler = pcu_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - PCU_InitialStudy pcu(prescaler, clock_gen, saps, bat, compo_step_time); + PCU_InitialStudy pcu(prescaler, clock_generator, saps, bat, compo_step_time); return pcu; } diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index 1dc2f9a79..b56712196 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -11,14 +11,14 @@ /* * @fn InitPCU_InitialStudy * @brief Initialize function of BAT - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] pcu_id: Power Control Unit ID * @param [in] fname: Path to initialize file * @param [in] sap: Solar Array Panel infomation * @param [in] bat: Battery information * @param [in] compo_step_time: Component step time [sec] */ -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_gen, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index 250289456..d72694312 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -9,7 +9,7 @@ #include "library/initialize/initialize_file_access.hpp" -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) { IniAccess sap_conf(fname); @@ -40,13 +40,14 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons double transmission_efficiency; transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); - SAP sap(prescaler, clock_gen, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, transmission_efficiency, srp, - local_celes_info, compo_step_time); + SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, + transmission_efficiency, srp, local_celes_info, compo_step_time); return sap; } -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, double compo_step_time) { +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, + double compo_step_time) { IniAccess sap_conf(fname); const std::string st_sap_id = std::to_string(sap_id); @@ -76,8 +77,8 @@ SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, cons double transmission_efficiency; transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); - SAP sap(prescaler, clock_gen, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, transmission_efficiency, srp, - compo_step_time); + SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, + transmission_efficiency, srp, compo_step_time); return sap; } diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index 8992af598..ff3bba712 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -11,25 +11,26 @@ /* * @fn InitSAP * @brief Initialize function of BAT - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID * @param [in] fname: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time); /* * @fn InitSAP * @brief Initialize function of BAT - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID * @param [in] fname: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_gen, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, double compo_step_time); +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, + double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index b86b19aa9..32318e134 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -9,8 +9,9 @@ #include #include -PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time) - : Component(prescaler, clock_gen), +PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, + double compo_step_time) + : Component(prescaler, clock_generator), saps_(saps), bat_(bat), cc_charge_current_(bat->GetCCChargeCurrent()), @@ -20,8 +21,8 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge power_consumption_ = 0.0; } -PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_gen, const std::vector saps, BAT* bat) - : Component(10, clock_gen), +PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, BAT* bat) + : Component(10, clock_generator), saps_(saps), bat_(bat), cc_charge_current_(bat->GetCCChargeCurrent()), diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index b5ab9ed54..310f2ef46 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -19,20 +19,20 @@ class PCU_InitialStudy : public Component, public ILoggable { * @fn PCU_InitialStudy * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels * @param [in] bat: Battery * @param [in] compo_step_time: Component step time [sec] */ - PCU_InitialStudy(const int prescaler, ClockGenerator* clock_gen, const std::vector saps, BAT* bat, double compo_step_time); + PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, double compo_step_time); /** * @fn PCU_InitialStudy * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels * @param [in] bat: Battery */ - PCU_InitialStudy(ClockGenerator* clock_gen, const std::vector saps, BAT* bat); + PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, BAT* bat); /** * @fn ~PCU_InitialStudy * @brief Destructor diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index 0ca8e2692..4a087cc13 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -4,9 +4,9 @@ */ #include "power_control_unit.hpp" -PCU::PCU(ClockGenerator* clock_gen) : Component(1, clock_gen) {} +PCU::PCU(ClockGenerator* clock_generator) : Component(1, clock_generator) {} -PCU::PCU(int prescaler, ClockGenerator* clock_gen) : Component(prescaler, clock_gen) {} +PCU::PCU(int prescaler, ClockGenerator* clock_generator) : Component(prescaler, clock_generator) {} PCU::~PCU() {} diff --git a/src/components/real/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp index 75029a2f3..431030437 100644 --- a/src/components/real/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -21,16 +21,16 @@ class PCU : public Component, public ILoggable { /** * @fn PCU * @brief Constructor - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator */ - PCU(ClockGenerator* clock_gen); + PCU(ClockGenerator* clock_generator); /** * @fn PCU * @brief Constructor * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator */ - PCU(int prescaler, ClockGenerator* clock_gen); + PCU(int prescaler, ClockGenerator* clock_generator); /** * @fn ~PCU * @brief Destructor diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 16351caba..6a4b174b4 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -8,10 +8,10 @@ #include #include -SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, +SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -26,10 +26,10 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s power_generation_ = 0.0; } -SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, +SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -43,10 +43,10 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_s power_generation_ = 0.0; } -SAP::SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, +SAP::SAP(ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) - : Component(10, clock_gen), + : Component(10, clock_generator), id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 5ae3b795b..534514da5 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -19,7 +19,7 @@ class SAP : public Component, public ILoggable { * @fn SAP * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells @@ -31,14 +31,14 @@ class SAP : public Component, public ILoggable { * @param [in] local_celes_info: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, + SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time); /** * @fn SAP * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells @@ -49,14 +49,14 @@ class SAP : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] compo_step_time: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, + SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time); /** * @fn SAP * @brief Constructor without prescaler * @note prescaler is set as 10, compo_step_sec is set as - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells @@ -67,7 +67,7 @@ class SAP : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SAP(ClockGenerator* clock_gen, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, + SAP(ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** diff --git a/src/components/real/propulsion/initialize_simple_thruster.cpp b/src/components/real/propulsion/initialize_simple_thruster.cpp index e3cd4ef8e..3743a2792 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.cpp +++ b/src/components/real/propulsion/initialize_simple_thruster.cpp @@ -8,7 +8,7 @@ #include "library/initialize/initialize_file_access.hpp" -SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { IniAccess thruster_conf(fname); std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); @@ -31,11 +31,11 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, co double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; - SimpleThruster thruster(prescaler, clock_gen, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); + SimpleThruster thruster(prescaler, clock_generator, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); return thruster; } -SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics) { IniAccess thruster_conf(fname); std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); @@ -60,6 +60,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_po power_port->InitializeWithInitializeFile(fname); - SimpleThruster thruster(prescaler, clock_gen, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); + SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, + dynamics); return thruster; } diff --git a/src/components/real/propulsion/initialize_simple_thruster.hpp b/src/components/real/propulsion/initialize_simple_thruster.hpp index 52f604077..ddea0706a 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.hpp +++ b/src/components/real/propulsion/initialize_simple_thruster.hpp @@ -11,25 +11,25 @@ /** * @fn InitSimpleThruster * @brief Initialize function os SimpleThruster - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] thruster_id: Thruster ID * @param [in] fname: Path to initialize file * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ -SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, int thruster_id, const std::string fname, const Structure* structure, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics); /** * @fn InitSimpleThruster * @brief Initialize function os SimpleThruster - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] thruster_id: Thruster ID * @param [in] fname: Path to initialize file * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ -SimpleThruster InitSimpleThruster(ClockGenerator* clock_gen, PowerPort* power_port, int thruster_id, const std::string fname, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string fname, const Structure* structure, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 37dbd2983..0b4e7a8cc 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -9,10 +9,10 @@ #include // Constructor -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, const int id, const Vector<3> thruster_pos_b, +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) - : Component(prescaler, clock_gen), + : Component(prescaler, clock_generator), id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), @@ -23,10 +23,10 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, c Initialize(mag_err, dir_err); } -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, - const Structure* structure, const Dynamics* dynamics) - : Component(prescaler, clock_gen, power_port), +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, + const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, + const double dir_err, const Structure* structure, const Dynamics* dynamics) + : Component(prescaler, clock_generator, power_port), id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 55a04b24e..5c4feebec 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -25,7 +25,7 @@ class SimpleThruster : public Component, public ILoggable { * @fn SimpleThruster * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] id: Thruster ID * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame @@ -35,13 +35,13 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_gen, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics); /** * @fn SimpleThruster * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update - * @param [in] clock_gen: Clock generator + * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Thruster ID * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] @@ -52,7 +52,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_gen, PowerPort* power_port, const int id, const Vector<3> thruster_pos_b, + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics); /** From a2a1e1fddaf1b6852b0b2d53ed6121a465b208d6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 12:47:43 +0100 Subject: [PATCH 0771/1086] Fix MainRoutine argument name --- src/components/examples/example_change_structure.cpp | 4 ++-- src/components/examples/example_change_structure.hpp | 2 +- src/components/examples/example_i2c_controller_for_hils.cpp | 4 ++-- src/components/examples/example_i2c_controller_for_hils.hpp | 2 +- src/components/examples/example_i2c_target_for_hils.cpp | 4 ++-- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- .../examples/example_serial_communication_for_hils.cpp | 4 ++-- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.cpp | 4 ++-- .../examples/example_serial_communication_with_obc.hpp | 4 ++-- 10 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/components/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp index 714524a12..f5c17b52b 100644 --- a/src/components/examples/example_change_structure.cpp +++ b/src/components/examples/example_change_structure.cpp @@ -10,8 +10,8 @@ ExampleChangeStructure::ExampleChangeStructure(ClockGenerator* clock_generator, ExampleChangeStructure::~ExampleChangeStructure() {} -void ExampleChangeStructure::MainRoutine(int count) { - if (count > 1000) { +void ExampleChangeStructure::MainRoutine(const int time_count) { + if (time_count > 1000) { // Mass structure_->GetToSetKinematicsParams().SetMass_kg(100.0); // Center of gravity diff --git a/src/components/examples/example_change_structure.hpp b/src/components/examples/example_change_structure.hpp index 16fc5cae0..916d1751d 100644 --- a/src/components/examples/example_change_structure.hpp +++ b/src/components/examples/example_change_structure.hpp @@ -35,7 +35,7 @@ class ExampleChangeStructure : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** diff --git a/src/components/examples/example_i2c_controller_for_hils.cpp b/src/components/examples/example_i2c_controller_for_hils.cpp index 296bd9040..1924ec1c8 100644 --- a/src/components/examples/example_i2c_controller_for_hils.cpp +++ b/src/components/examples/example_i2c_controller_for_hils.cpp @@ -11,8 +11,8 @@ ExampleI2cControllerForHils::ExampleI2cControllerForHils(const int prescaler, Cl ExampleI2cControllerForHils::~ExampleI2cControllerForHils() {} -void ExampleI2cControllerForHils::MainRoutine(int count) { - UNUSED(count); +void ExampleI2cControllerForHils::MainRoutine(const int time_count) { + UNUSED(time_count); RequestTlm(); Receive(); diff --git a/src/components/examples/example_i2c_controller_for_hils.hpp b/src/components/examples/example_i2c_controller_for_hils.hpp index af7e2b2e5..51b948708 100644 --- a/src/components/examples/example_i2c_controller_for_hils.hpp +++ b/src/components/examples/example_i2c_controller_for_hils.hpp @@ -45,7 +45,7 @@ class ExampleI2cControllerForHils : public Component, public I2cController { * @fn MainRoutine * @brief Main routine to receive command and send telemetry */ - void MainRoutine(int count); + void MainRoutine(const int time_count); private: /** diff --git a/src/components/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp index 50219144a..49733b0be 100644 --- a/src/components/examples/example_i2c_target_for_hils.cpp +++ b/src/components/examples/example_i2c_target_for_hils.cpp @@ -12,8 +12,8 @@ ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGener ExampleI2cTargetForHils::~ExampleI2cTargetForHils() {} -void ExampleI2cTargetForHils::MainRoutine(int count) { - UNUSED(count); +void ExampleI2cTargetForHils::MainRoutine(const int time_count) { + UNUSED(time_count); // update telemetry data const unsigned char kTlmSize = 5; diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index ced67e411..8f50b5984 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -46,7 +46,7 @@ class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationW * @fn MainRoutine * @brief Main routine to receive command and send telemetry */ - void MainRoutine(int count); + void MainRoutine(const int time_count); private: unsigned char tlm_counter_ = 0; //!< Telemetry counter diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index 2985ee22a..e1bec08a1 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -53,8 +53,8 @@ int ExampleSerialCommunicationForHils::GenerateTelemetry() { return 0; } -void ExampleSerialCommunicationForHils::MainRoutine(int count) { - UNUSED(count); +void ExampleSerialCommunicationForHils::MainRoutine(const int time_count) { + UNUSED(time_count); ReceiveCommand(0, kMemorySize); SendTelemetry(0); diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index ce8fe9915..ef6ea5b98 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -48,7 +48,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @fn MainRoutine * @brief Main routine to receive command and send telemetry */ - void MainRoutine(int count); + void MainRoutine(const int time_count); private: const static int kMemorySize = 4; //!< Memory size diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index 590d01598..037a8ded7 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -44,8 +44,8 @@ int ExampleSerialCommunicationWithObc::GenerateTelemetry() { tx_buffer_.assign(std::begin(tx_buff), std::end(tx_buff)); return sizeof(tx_buff); } -void ExampleSerialCommunicationWithObc::MainRoutine(int count) { - UNUSED(count); +void ExampleSerialCommunicationWithObc::MainRoutine(const int time_count) { + UNUSED(time_count); ReceiveCommand(0, 5); SendTelemetry(0); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index a54121396..44294a0b8 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -57,7 +57,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @fn MainRoutine * @brief Main routine to receive command and send telemetry */ - void MainRoutine(int count); + void MainRoutine(const int time_count); // Override functions for IGPIOCompo /** @@ -73,7 +73,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica unsigned char tx_buff[MAX_MEMORY_LEN]; //!< TX (Telemetry send) buffer unsigned char rx_buff[MAX_MEMORY_LEN]; //!< RX (Command receive) buffer - // Override functions for ObcComunication + // Override functions for ObcCommunication /** * @fn ParseCommand * @brief Parse command received from OBC From 1001644aecaf4d39d587e68227c18528e3246075 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 12:49:31 +0100 Subject: [PATCH 0772/1086] Fix function argument --- src/components/base/uart_communication_with_obc.hpp | 2 +- .../examples/example_serial_communication_for_hils.cpp | 4 ++-- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.cpp | 4 ++-- .../examples/example_serial_communication_with_obc.hpp | 2 +- 5 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index dd5521757..0f7a1c3dc 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -119,7 +119,7 @@ class UartCommunicationWithObc { * @brief Pure virtual function for parse command feature * @return Error code (ret<=0 means error, ret>0 means fine) */ - virtual int ParseCommand(const int cmd_size) = 0; + virtual int ParseCommand(const int command_size) = 0; /** * @fn GenerateTelemetry * @brief Pure virtual function for generate telemetry feature diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index e1bec08a1..f6a312435 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -13,8 +13,8 @@ ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenera ExampleSerialCommunicationForHils::~ExampleSerialCommunicationForHils() {} -int ExampleSerialCommunicationForHils::ParseCommand(const int cmd_size) { - UNUSED(cmd_size); +int ExampleSerialCommunicationForHils::ParseCommand(const int command_size) { + UNUSED(command_size); if (mode_id_ == 1) { for (int i = 0; i < kMemorySize; i++) { diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index ef6ea5b98..7f26a503c 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -63,7 +63,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @fn ParseCommand * @brief Parse command received from OBC */ - int ParseCommand(const int cmd_size) override; + int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry * @brief Generate telemetry send to OBC diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index 037a8ded7..9010c11c7 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -25,8 +25,8 @@ int ExampleSerialCommunicationWithObc::Initialize() { ExampleSerialCommunicationWithObc::~ExampleSerialCommunicationWithObc() {} -int ExampleSerialCommunicationWithObc::ParseCommand(const int cmd_size) { - if (cmd_size < 4) { +int ExampleSerialCommunicationWithObc::ParseCommand(const int command_size) { + if (command_size < 4) { return -1; } if (rx_buffer_[0] != 'S' || rx_buffer_[1] != 'E' || rx_buffer_[2] != 'T') { diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 44294a0b8..ee6c8b9dc 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -78,7 +78,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @fn ParseCommand * @brief Parse command received from OBC */ - int ParseCommand(const int cmd_size) override; + int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry * @brief Generate telemetry send to OBC From ca428c60084f0268c29b76c551f0faab7c68a8a2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 12:52:43 +0100 Subject: [PATCH 0773/1086] Fix private variables --- .../examples/example_serial_communication_with_obc.cpp | 6 +++--- .../examples/example_serial_communication_with_obc.hpp | 9 ++++----- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index 9010c11c7..2d4f74c5e 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -39,10 +39,10 @@ int ExampleSerialCommunicationWithObc::ParseCommand(const int command_size) { } int ExampleSerialCommunicationWithObc::GenerateTelemetry() { for (int i = 0; i < MAX_MEMORY_LEN; i++) { - tx_buff[i] = (unsigned char)memory[i]; + tx_buffer[i] = (unsigned char)memory[i]; } - tx_buffer_.assign(std::begin(tx_buff), std::end(tx_buff)); - return sizeof(tx_buff); + tx_buffer_.assign(std::begin(tx_buffer), std::end(tx_buffer)); + return sizeof(tx_buffer); } void ExampleSerialCommunicationWithObc::MainRoutine(const int time_count) { UNUSED(time_count); diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index ee6c8b9dc..2ee6df656 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -67,11 +67,10 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica void GpioStateChanged(int port_id, bool isPosedge); private: - const static int MAX_MEMORY_LEN = 100; //!< Maximum memory length - std::vector memory; //!< Memory for telemetry generation - char memoryc[100]; //!< Memory in char array - unsigned char tx_buff[MAX_MEMORY_LEN]; //!< TX (Telemetry send) buffer - unsigned char rx_buff[MAX_MEMORY_LEN]; //!< RX (Command receive) buffer + const static int MAX_MEMORY_LEN = 100; //!< Maximum memory length + std::vector memory; //!< Memory for telemetry generation + unsigned char tx_buffer[MAX_MEMORY_LEN]; //!< TX (Telemetry send) buffer + unsigned char rx_buffer[MAX_MEMORY_LEN]; //!< RX (Command receive) buffer // Override functions for ObcCommunication /** From 44b3392e5a5e25ff36cfe1c6eda964adb98185b9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:08:28 +0100 Subject: [PATCH 0774/1086] Fix private variables --- .../example_serial_communication_with_obc.cpp | 18 +++++++++--------- .../example_serial_communication_with_obc.hpp | 6 ++---- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index 2d4f74c5e..ace07e25f 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -17,8 +17,8 @@ ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenera } int ExampleSerialCommunicationWithObc::Initialize() { - for (int i = 0; i < MAX_MEMORY_LEN; i++) { - memory.push_back(0); + for (int i = 0; i < kMaxMemoryLength; i++) { + memory_.push_back(0); } return 0; } @@ -32,17 +32,17 @@ int ExampleSerialCommunicationWithObc::ParseCommand(const int command_size) { if (rx_buffer_[0] != 'S' || rx_buffer_[1] != 'E' || rx_buffer_[2] != 'T') { return -1; } - memory.pop_back(); - memory.insert(memory.begin(), rx_buffer_[3]); - memory[MAX_MEMORY_LEN - 1] = '\n'; + memory_.pop_back(); + memory_.insert(memory_.begin(), rx_buffer_[3]); + memory_[kMaxMemoryLength - 1] = '\n'; return 0; } int ExampleSerialCommunicationWithObc::GenerateTelemetry() { - for (int i = 0; i < MAX_MEMORY_LEN; i++) { - tx_buffer[i] = (unsigned char)memory[i]; + for (int i = 0; i < kMaxMemoryLength; i++) { + tx_buffer_[i] = (unsigned char)memory_[i]; } - tx_buffer_.assign(std::begin(tx_buffer), std::end(tx_buffer)); - return sizeof(tx_buffer); + tx_buffer_.assign(std::begin(tx_buffer_), std::end(tx_buffer_)); + return sizeof(tx_buffer_); } void ExampleSerialCommunicationWithObc::MainRoutine(const int time_count) { UNUSED(time_count); diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 2ee6df656..5590d7b51 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -67,10 +67,8 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica void GpioStateChanged(int port_id, bool isPosedge); private: - const static int MAX_MEMORY_LEN = 100; //!< Maximum memory length - std::vector memory; //!< Memory for telemetry generation - unsigned char tx_buffer[MAX_MEMORY_LEN]; //!< TX (Telemetry send) buffer - unsigned char rx_buffer[MAX_MEMORY_LEN]; //!< RX (Command receive) buffer + const static int kMaxMemoryLength = 100; //!< Maximum memory length + std::vector memory_; //!< Memory for telemetry generation // Override functions for ObcCommunication /** From 68b6159d38e6f474bca6f04b4690ff7c8e003705 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:11:27 +0100 Subject: [PATCH 0775/1086] Fix function arguments --- src/components/ideal/force_generator.cpp | 4 ++-- src/components/ideal/force_generator.hpp | 2 +- src/components/ideal/torque_generator.cpp | 4 ++-- src/components/ideal/torque_generator.hpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 1224ae110..458bb0f49 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -19,8 +19,8 @@ ForceGenerator::ForceGenerator(const int prescaler, ClockGenerator* clock_genera ForceGenerator::~ForceGenerator() {} -void ForceGenerator::MainRoutine(int count) { - UNUSED(count); +void ForceGenerator::MainRoutine(const int time_count) { + UNUSED(time_count); generated_force_b_N_ = ordered_force_b_N_; diff --git a/src/components/ideal/force_generator.hpp b/src/components/ideal/force_generator.hpp index d4fdd8ac3..6439f4d10 100644 --- a/src/components/ideal/force_generator.hpp +++ b/src/components/ideal/force_generator.hpp @@ -40,7 +40,7 @@ class ForceGenerator : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int count); + void MainRoutine(const int time_count); /** * @fn PowerOffRoutine * @brief Power off routine to stop force generation diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 43a616b03..f160a2c04 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -19,8 +19,8 @@ TorqueGenerator::TorqueGenerator(const int prescaler, ClockGenerator* clock_gene TorqueGenerator::~TorqueGenerator() {} -void TorqueGenerator::MainRoutine(int count) { - UNUSED(count); +void TorqueGenerator::MainRoutine(const int time_count) { + UNUSED(time_count); generated_torque_b_Nm_ = ordered_torque_b_Nm_; diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index bba4a2a0b..db75006ad 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -40,7 +40,7 @@ class TorqueGenerator : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate torque generation */ - void MainRoutine(int count); + void MainRoutine(const int time_count); /** * @fn PowerOffRoutine * @brief Power off routine to stop torque generation From d091d7fd34fb5f517865c989baa617472141ed7d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:15:21 +0100 Subject: [PATCH 0776/1086] Remove using --- src/components/real/aocs/gnss_receiver.cpp | 37 ++++++------- src/components/real/aocs/gnss_receiver.hpp | 60 +++++++++++----------- 2 files changed, 48 insertions(+), 49 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 7b7c66f14..0c68b1add 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -10,8 +10,9 @@ #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) + const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, + const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, + const SimulationTime* simtime) : Component(prescaler, clock_generator), id_(id), ch_max_(ch_max), @@ -27,8 +28,8 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, gnss_satellites_(gnss_satellites), simtime_(simtime) {} GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const std::string gnss_id, - const int ch_max, const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, - const double half_width, const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, + const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, + const double half_width, const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime) : Component(prescaler, clock_generator, power_port), id_(id), @@ -48,7 +49,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, void GNSSReceiver::MainRoutine(int count) { UNUSED(count); - Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); + libra::Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); CheckAntenna(pos_true_eci_, q_i2b); @@ -69,21 +70,21 @@ void GNSSReceiver::MainRoutine(int count) { } } -void GNSSReceiver::CheckAntenna(const Vector<3> pos_true_eci_, Quaternion q_i2b) { +void GNSSReceiver::CheckAntenna(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { if (antenna_model_ == SIMPLE) CheckAntennaSimple(pos_true_eci_, q_i2b); else if (antenna_model_ == CONE) CheckAntennaCone(pos_true_eci_, q_i2b); } -void GNSSReceiver::CheckAntennaSimple(const Vector<3> pos_true_eci_, Quaternion q_i2b) { +void GNSSReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { // Simplest model // GNSS sats are visible when antenna directs anti-earth direction // antenna normal vector at inertial frame - Vector<3> antenna_direction_c(0.0); + libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); - Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); + libra::Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); double inner = InnerProduct(pos_true_eci_, antenna_direction_i); if (inner <= 0) @@ -92,16 +93,16 @@ void GNSSReceiver::CheckAntennaSimple(const Vector<3> pos_true_eci_, Quaternion is_gnss_sats_visible_ = 1; } -void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_i2b) { +void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { // Cone model - Vector<3> gnss_sat_pos_i, ant_pos_i, ant2gnss_i, ant2gnss_i_n, sat2ant_i; + libra::Vector<3> gnss_sat_pos_i, ant_pos_i, ant2gnss_i, ant2gnss_i_n, sat2ant_i; vec_gnssinfo_.clear(); // antenna normal vector at inertial frame - Vector<3> antenna_direction_c(0.0); + libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); - Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); + libra::Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); sat2ant_i = q_i2b.InverseFrameConversion(antenna_position_b_); ant_pos_i = pos_true_eci_ + sat2ant_i; @@ -152,8 +153,8 @@ void GNSSReceiver::CheckAntennaCone(const Vector<3> pos_true_eci_, Quaternion q_ is_gnss_sats_visible_ = 0; } -void GNSSReceiver::SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::string gnss_id) { - Vector<3> ant2gnss_b, ant2gnss_c; +void GNSSReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_i2b, std::string gnss_id) { + libra::Vector<3> ant2gnss_b, ant2gnss_c; ant2gnss_b = q_i2b.FrameConversion(ant2gnss_i); ant2gnss_c = q_b2c_.FrameConversion(ant2gnss_b); @@ -166,7 +167,7 @@ void GNSSReceiver::SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::stri vec_gnssinfo_.push_back(gnss_info_new); } -void GNSSReceiver::AddNoise(Vector<3> location_true_eci, Vector<3> location_true_ecef) { +void GNSSReceiver::AddNoise(libra::Vector<3> location_true_eci, libra::Vector<3> location_true_ecef) { // Simplest noise model position_eci_[0] = location_true_eci[0] + nrs_eci_x_; position_eci_[1] = location_true_eci[1] + nrs_eci_y_; diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index c40d921e0..d1825b479 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -15,8 +15,6 @@ #include "../../base/component.hpp" -using libra::Vector; - /** * @enum AntennaModel * @brief Antenna pattern model to emulate GNSS antenna @@ -60,8 +58,8 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] simtime: Simulation time information */ GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, + const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); /** * @fn GNSSReceiver * @brief Constructor with power port @@ -80,8 +78,8 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] simtime: Simulation time information */ GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const Vector<3> ant_pos_b, const Quaternion q_b2c, const double half_width, - const Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, + const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); // Override functions for Component /** @@ -101,27 +99,27 @@ class GNSSReceiver : public Component, public ILoggable { * @fn GetPositionECI * @brief Return Observed position in the ECI frame [m] */ - inline const Vector<3> GetPositionECI(void) const { return position_eci_; } + inline const libra::Vector<3> GetPositionECI(void) const { return position_eci_; } /** * @fn GetPositionECEF * @brief Return Observed position in the ECEF frame [m] */ - inline const Vector<3> GetPositionECEF(void) const { return position_ecef_; } + inline const libra::Vector<3> GetPositionECEF(void) const { return position_ecef_; } /** * @fn GetPositionLLH * @brief Return Observed position in the LLH frame [m] */ - inline const Vector<3> GetPositionLLH(void) const { return position_llh_; } + inline const libra::Vector<3> GetPositionLLH(void) const { return position_llh_; } /** * @fn GetVelocityECI * @brief Return Observed velocity in the ECI frame [m/s] */ - inline const Vector<3> GetVelocityECI(void) const { return velocity_eci_; } + inline const libra::Vector<3> GetVelocityECI(void) const { return velocity_eci_; } /** * @fn GetVelocityECEF * @brief Return Observed velocity in the ECEF frame [m/s] */ - inline const Vector<3> GetVelocityECEF(void) const { return velocity_ecef_; } + inline const libra::Vector<3> GetVelocityECEF(void) const { return velocity_ecef_; } // Override ILoggable /** @@ -137,10 +135,10 @@ class GNSSReceiver : public Component, public ILoggable { protected: // Parameters for receiver - const int id_; //!< Receiver ID - const int ch_max_; //!< Maximum number of channels - Vector<3> antenna_position_b_; //!< GNSS antenna position at the body-fixed frame [m] - Quaternion q_b2c_; //!< Quaternion from body frame to component frame (antenna frame) + const int id_; //!< Receiver ID + const int ch_max_; //!< Maximum number of channels + libra::Vector<3> antenna_position_b_; //!< GNSS antenna position at the body-fixed frame [m] + libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame (antenna frame) libra::NormalRand nrs_eci_x_, nrs_eci_y_, nrs_eci_z_; //!< Random noise for each axis @@ -149,17 +147,17 @@ class GNSSReceiver : public Component, public ILoggable { AntennaModel antenna_model_; //!< Antenna model // Calculated values - Vector<3> position_eci_{0.0}; //!< Observed position in the ECI frame [m] - Vector<3> velocity_eci_{0.0}; //!< Observed velocity in the ECI frame [m/s] - Vector<3> position_ecef_{0.0}; //!< Observed position in the ECEF frame [m] - Vector<3> velocity_ecef_{0.0}; //!< Observed velocity in the ECEF frame [m/s] - Vector<3> position_llh_{0.0}; //!< Observed position in the geodetic frame [rad,rad,m] TODO: use GeodeticPosition class - UTC utc_ = {2000, 1, 1, 0, 0, 0.0}; //!< Observed time in UTC [year, month, day, hour, min, sec] - unsigned int gpstime_week_ = 0; //!< Observed GPS time week part - double gpstime_sec_ = 0.0; //!< Observed GPS time second part - int is_gnss_sats_visible_ = 0; //!< Flag for GNSS satellite is visible or not - int gnss_sats_visible_num_ = 0; //!< Number of visible GNSS satellites - std::vector vec_gnssinfo_; //!< Information List of visible GNSS satellites + libra::Vector<3> position_eci_{0.0}; //!< Observed position in the ECI frame [m] + libra::Vector<3> velocity_eci_{0.0}; //!< Observed velocity in the ECI frame [m/s] + libra::Vector<3> position_ecef_{0.0}; //!< Observed position in the ECEF frame [m] + libra::Vector<3> velocity_ecef_{0.0}; //!< Observed velocity in the ECEF frame [m/s] + libra::Vector<3> position_llh_{0.0}; //!< Observed position in the geodetic frame [rad,rad,m] TODO: use GeodeticPosition class + UTC utc_ = {2000, 1, 1, 0, 0, 0.0}; //!< Observed time in UTC [year, month, day, hour, min, sec] + unsigned int gpstime_week_ = 0; //!< Observed GPS time week part + double gpstime_sec_ = 0.0; //!< Observed GPS time second part + int is_gnss_sats_visible_ = 0; //!< Flag for GNSS satellite is visible or not + int gnss_sats_visible_num_ = 0; //!< Number of visible GNSS satellites + std::vector vec_gnssinfo_; //!< Information List of visible GNSS satellites // References const Dynamics* dynamics_; //!< Dynamics of spacecraft @@ -174,7 +172,7 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] location_true: True position of the spacecraft in the ECI frame [m] * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntenna(Vector<3> location_true, Quaternion q_i2b); + void CheckAntenna(libra::Vector<3> location_true, libra::Quaternion q_i2b); /** * @fn CheckAntennaSimple * @brief Check the antenna can detect GNSS signal with Simple mode @@ -182,7 +180,7 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] location_true: True position of the spacecraft in the ECI frame [m] * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntennaSimple(Vector<3> location_true, Quaternion q_i2b); + void CheckAntennaSimple(libra::Vector<3> location_true, libra::Quaternion q_i2b); /** * @fn CheckAntennaCone * @brief Check the antenna can detect GNSS signal with Cone mode @@ -190,7 +188,7 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] location_true: True position of the spacecraft in the ECI frame [m] * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntennaCone(Vector<3> location_true, Quaternion q_i2b); + void CheckAntennaCone(libra::Vector<3> location_true, libra::Quaternion q_i2b); /** * @fn SetGnssInfo * @brief Calculate and set the GnssInfo values of target GNSS satellite @@ -198,14 +196,14 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame * @param [in] gnss_id: ID of target GNSS satellite */ - void SetGnssInfo(Vector<3> ant2gnss_i, Quaternion q_i2b, std::string gnss_id); + void SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_i2b, std::string gnss_id); /** * @fn AddNoise * @brief Substitutional method for "Measure" in other sensor models inherited Sensor class * @param [in] location_true_eci: True position of the spacecraft in the ECI frame [m] * @param [in] location_true_ecef: True position of the spacecraft in the ECEF frame [m] */ - void AddNoise(Vector<3> location_true_eci, Vector<3> location_true_ecef); + void AddNoise(libra::Vector<3> location_true_eci, libra::Vector<3> location_true_ecef); /** * @fn ConvertJulianDayToGPSTime * @brief Convert Julian day to GPS time From a47e79c19e43f94aa565fe8f5f65160cecdb7b0b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:21:01 +0100 Subject: [PATCH 0777/1086] Fix function arguments --- src/components/real/aocs/gnss_receiver.cpp | 40 +++++++++---------- src/components/real/aocs/gnss_receiver.hpp | 31 +++++++------- src/components/real/aocs/gyro_sensor.cpp | 8 ++-- src/components/real/aocs/gyro_sensor.hpp | 8 ++-- .../real/aocs/initialize_gnss_receiver.cpp | 22 +++++----- .../real/aocs/initialize_gnss_receiver.hpp | 8 ++-- .../real/aocs/initialize_gyro_sensor.cpp | 12 +++--- .../real/aocs/initialize_magnetometer.cpp | 15 +++---- .../real/aocs/initialize_magnetorquer.cpp | 16 ++++---- .../real/aocs/initialize_reaction_wheel.cpp | 10 ++--- .../real/aocs/initialize_star_sensor.cpp | 18 ++++----- .../real/aocs/initialize_sun_sensor.cpp | 14 +++---- src/components/real/aocs/magnetometer.cpp | 8 ++-- src/components/real/aocs/magnetometer.hpp | 8 ++-- src/components/real/aocs/magnetorquer.cpp | 8 ++-- src/components/real/aocs/magnetorquer.hpp | 8 ++-- src/components/real/aocs/reaction_wheel.cpp | 16 ++++---- src/components/real/aocs/reaction_wheel.hpp | 12 +++--- .../real/aocs/reaction_wheel_jitter.cpp | 4 +- .../real/aocs/reaction_wheel_jitter.hpp | 6 +-- src/components/real/aocs/star_sensor.cpp | 8 ++-- src/components/real/aocs/star_sensor.hpp | 10 ++--- src/components/real/aocs/sun_sensor.cpp | 17 ++++---- src/components/real/aocs/sun_sensor.hpp | 13 +++--- src/components/real/communication/antenna.cpp | 8 ++-- src/components/real/communication/antenna.hpp | 8 ++-- .../real/communication/initialize_antenna.cpp | 7 ++-- .../real/mission/initialize_telescope.cpp | 6 +-- src/components/real/mission/telescope.cpp | 4 +- src/components/real/mission/telescope.hpp | 2 +- 30 files changed, 182 insertions(+), 173 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 0c68b1add..0e27871b6 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -10,41 +10,41 @@ #include GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, - const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, - const SimulationTime* simtime) + const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, + const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator), id_(id), ch_max_(ch_max), - antenna_position_b_(ant_pos_b), - q_b2c_(q_b2c), - nrs_eci_x_(0.0, noise_std[0], global_randomization.MakeSeed()), - nrs_eci_y_(0.0, noise_std[1], global_randomization.MakeSeed()), - nrs_eci_z_(0.0, noise_std[2], global_randomization.MakeSeed()), - half_width_(half_width), + antenna_position_b_(antenna_posision_b_m), + q_b2c_(quaternion_b2c), + nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), + nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), + nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), + half_width_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), dynamics_(dynamics), gnss_satellites_(gnss_satellites), - simtime_(simtime) {} + simtime_(simulation_time) {} GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const std::string gnss_id, - const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, - const double half_width, const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, - const SimulationTime* simtime) + const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, + const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, + const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator, power_port), id_(id), ch_max_(ch_max), - antenna_position_b_(ant_pos_b), - q_b2c_(q_b2c), - nrs_eci_x_(0.0, noise_std[0], global_randomization.MakeSeed()), - nrs_eci_y_(0.0, noise_std[1], global_randomization.MakeSeed()), - nrs_eci_z_(0.0, noise_std[2], global_randomization.MakeSeed()), - half_width_(half_width), + antenna_position_b_(antenna_posision_b_m), + q_b2c_(quaternion_b2c), + nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), + nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), + nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), + half_width_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), dynamics_(dynamics), gnss_satellites_(gnss_satellites), - simtime_(simtime) {} + simtime_(simulation_time) {} void GNSSReceiver::MainRoutine(int count) { UNUSED(count); diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index d1825b479..cebe64ca2 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -46,20 +46,22 @@ class GNSSReceiver : public Component, public ILoggable { * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator + * @param [in] id: Component ID * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels * @param [in] antenna_model: Antenna model - * @param [in] ant_pos_b: GNSS antenna position at the body-fixed frame [m] - * @param [in] q_b2c: Quaternion from body frame to component frame (antenna frame) - * @param [in] half_width: Half width of the antenna cone model [rad] - * @param [in] noise_std: Standard deviation of normal random noise in the ECI frame [m] + * @param [in] antenna_posision_b_m: GNSS antenna position at the body-fixed frame [m] + * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) + * @param [in] half_width_rad: Half width of the antenna cone model [rad] + * @param [in] noise_standard_deviation_m: Standard deviation of normal random noise in the ECI frame [m] * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS Satellites information - * @param [in] simtime: Simulation time information + * @param [in] simulation_time: Simulation time information */ GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, - const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, + const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); /** * @fn GNSSReceiver * @brief Constructor with power port @@ -69,17 +71,18 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels * @param [in] antenna_model: Antenna model - * @param [in] ant_pos_b: GNSS antenna position at the body-fixed frame [m] - * @param [in] q_b2c: Quaternion from body frame to component frame (antenna frame) - * @param [in] half_width: Half width of the antenna cone model [rad] - * @param [in] noise_std: Standard deviation of normal random noise in the ECI frame [m] + * @param [in] antenna_posision_b_m: GNSS antenna position at the body-fixed frame [m] + * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) + * @param [in] half_width_rad: Half width of the antenna cone model [rad] + * @param [in] noise_standard_deviation_m: Standard deviation of normal random noise in the ECI frame [m] * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS Satellites information - * @param [in] simtime: Simulation time information + * @param [in] simulation_time: Simulation time information */ GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> ant_pos_b, const libra::Quaternion q_b2c, const double half_width, - const libra::Vector<3> noise_std, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, + const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); // Override functions for Component /** diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index ff41bb730..6d01aff1d 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,13 +5,13 @@ #include "gyro_sensor.hpp" -Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, +Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), dynamics_(dynamics) {} Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const libra::Quaternion& q_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), dynamics_(dynamics) {} + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) + : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), dynamics_(dynamics) {} Gyro::~Gyro() {} diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index fe62b8e58..ca62382d0 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -28,10 +28,10 @@ class Gyro : public Component, public Sensor, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); /** * @fn Gyro @@ -41,11 +41,11 @@ class Gyro : public Component, public Sensor, public ILoggable { * @param [in] power_port: Power port * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const libra::Quaternion& q_b2c, const Dynamics* dynamics); + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); /** * @fn ~Gyro * @brief Destructor diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index 987c0e221..6e94ddf30 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -12,11 +12,11 @@ typedef struct _gnssrecever_param { int prescaler; AntennaModel antenna_model; Vector<3> antenna_pos_b; - Quaternion q_b2c; - double half_width; + Quaternion quaternion_b2c; + double half_width_rad; std::string gnss_id; int ch_max; - Vector<3> noise_std; + Vector<3> noise_standard_deviation_m; } GNSSReceiverParam; GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites, const int id) { @@ -40,32 +40,34 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli } gnssr_conf.ReadVector(GSection, "antenna_position_b_m", gnssreceiver_param.antenna_pos_b); - gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnssreceiver_param.q_b2c); - gnssreceiver_param.half_width = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); + gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnssreceiver_param.quaternion_b2c); + gnssreceiver_param.half_width_rad = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); gnssreceiver_param.gnss_id = gnssr_conf.ReadString(GSection, "gnss_id"); gnssreceiver_param.ch_max = gnssr_conf.ReadInt(GSection, "maximum_channel"); - gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnssreceiver_param.noise_std); + gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnssreceiver_param.noise_standard_deviation_m); return gnssreceiver_param; } GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, - gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); + gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, gnss_satellites, + simulation_time); return gnss_r; } GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simtime) { + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); // PowerPort power_port->InitializeWithInitializeFile(fname); GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, - gr_param.antenna_pos_b, gr_param.q_b2c, gr_param.half_width, gr_param.noise_std, dynamics, gnss_satellites, simtime); + gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, + gnss_satellites, simulation_time); return gnss_r; } diff --git a/src/components/real/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp index 284e8a928..8e13e11ba 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -16,10 +16,10 @@ * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information - * @param [in] simtime: Simulation time information + * @param [in] simulation_time: Simulation time information */ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); /** * @fn InitGNSSReceiver * @brief Initialize functions for GNSS Receiver with power port @@ -29,9 +29,9 @@ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information - * @param [in] simtime: Simulation time information + * @param [in] simulation_time: Simulation time information */ GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simtime); + const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 26fe1fdb5..a492c9248 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -14,15 +14,15 @@ Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); - Quaternion q_b2c; - gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", quaternion_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); - Gyro gyro(prescaler, clock_generator, sensor_base, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } @@ -34,8 +34,8 @@ Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); - Quaternion q_b2c; - gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", quaternion_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -45,6 +45,6 @@ Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor // PowerPort power_port->InitializeWithInitializeFile(fname); - Gyro gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, q_b2c, dynamics); + Gyro gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index b7d4feae3..7e3864a33 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,7 +7,8 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet) { +MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, + const GeomagneticField* magnet) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -16,13 +17,13 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const st int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion q_b2c; - magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); - MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, magnet); return magsensor; } @@ -36,8 +37,8 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion q_b2c; - magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); @@ -45,6 +46,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, // PowerPort power_port->InitializeWithInitializeFile(fname); - MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, q_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, magnet); return magsensor; } diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 6b8bed5b7..97800a771 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -25,8 +25,8 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons } } - Quaternion q_b2c; - magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); Vector max_c; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); @@ -45,8 +45,8 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons Vector nr_stddev_c; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); - MagTorquer magtorquer(prescaler, clock_generator, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, rw_limit_c, - nr_stddev_c, mag_env); + MagTorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, + rw_limit_c, nr_stddev_c, mag_env); return magtorquer; } @@ -69,8 +69,8 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port } } - Quaternion q_b2c; - magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); Vector max_c; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); @@ -92,7 +92,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port // PowerPort power_port->InitializeWithInitializeFile(fname); - MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, q_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, - rw_limit_c, nr_stddev_c, mag_env); + MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, + rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); return magtorquer; } diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index c51ba0082..cfd47a726 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -19,7 +19,7 @@ double jitter_update_interval; double inertia; double max_torque; double max_velocity; -libra::Quaternion q_b2c; +libra::Quaternion quaternion_b2c; libra::Vector<3> pos_b; double dead_time; libra::Vector<3> ordinary_lag_coef(1.0); @@ -56,7 +56,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double std::string direction_determination_mode; direction_determination_mode = rwmodel_conf.ReadString(RWsection, "direction_determination_mode"); if (direction_determination_mode == "QUATERNION") { - rwmodel_conf.ReadQuaternion(RWsection, "quaternion_b2c", q_b2c); + rwmodel_conf.ReadQuaternion(RWsection, "quaternion_b2c", quaternion_b2c); } else // direction_determination_mode == "DIRECTION" { libra::Vector<3> direction_b; @@ -64,7 +64,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double libra::Vector<3> direction_c(0.0); direction_c[2] = 1.0; libra::Quaternion q(direction_b, direction_c); - q_b2c = q.Conjugate(); + quaternion_b2c = q.Conjugate(); } rwmodel_conf.ReadVector(RWsection, "position_b_m", pos_b); @@ -102,7 +102,7 @@ RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::strin InitParams(actuator_id, file_name, prop_step, compo_update_step); RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, - max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, + max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); @@ -116,7 +116,7 @@ RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int power_port->InitializeWithInitializeFile(file_name); RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, - max_torque, max_velocity, q_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, + max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index 075dd23ab..206b7fd29 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -20,8 +20,8 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; double step_time = compo_step_time * prescaler; - Quaternion q_b2c; - STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); @@ -37,13 +37,13 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; - STT stt(prescaler, clock_generator, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, - earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); + STT stt(prescaler, clock_generator, sensor_id, quaternion_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, + sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); return stt; } -STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_env) { +STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, + const Dynamics* dynamics, const LocalEnvironment* local_env) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -53,8 +53,8 @@ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_i if (prescaler <= 1) prescaler = 1; double step_time = compo_step_time * prescaler; - Quaternion q_b2c; - STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); @@ -72,7 +72,7 @@ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_i power_port->InitializeWithInitializeFile(fname); - STT stt(prescaler, clock_generator, power_port, sensor_id, q_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, + STT stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); return stt; } diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index c8aad0b4b..28fd52111 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -20,8 +20,8 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string int prescaler = ss_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - libra::Quaternion q_b2c; - ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); + libra::Quaternion quaternion_b2c; + ss_conf.ReadQuaternion(Section, "quaternion_b2c", quaternion_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; detectable_angle_deg = ss_conf.ReadDouble(Section, "field_of_view_deg"); @@ -38,8 +38,8 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string double intensity_lower_threshold_percent; intensity_lower_threshold_percent = ss_conf.ReadDouble(Section, "intensity_lower_threshold_percent"); - SunSensor ss(prescaler, clock_generator, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, srp, - local_celes_info); + SunSensor ss(prescaler, clock_generator, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, + srp, local_celes_info); return ss; } @@ -53,8 +53,8 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int prescaler = ss_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - libra::Quaternion q_b2c; - ss_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); + libra::Quaternion quaternion_b2c; + ss_conf.ReadQuaternion(Section, "quaternion_b2c", quaternion_b2c); double detectable_angle_deg = 0.0, detectable_angle_rad = 0.0; detectable_angle_deg = ss_conf.ReadDouble(Section, "field_of_view_deg"); @@ -73,7 +73,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, power_port->InitializeWithInitializeFile(file_name); - SunSensor ss(prescaler, clock_generator, power_port, ss_id, q_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, + SunSensor ss(prescaler, clock_generator, power_port, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, srp, local_celes_info); return ss; } diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 7ad3a6bc9..11ef902c9 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -6,12 +6,12 @@ #include -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& q_b2c, +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), magnet_(magnet) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const Quaternion& q_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(q_b2c), magnet_(magnet) {} + const Quaternion& quaternion_b2c, const GeomagneticField* magnet) + : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 457d70ac5..2a8c22302 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -28,10 +28,10 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& q_b2c, + MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); /** * @fn MagSensor @@ -41,11 +41,11 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] power_port: Power port * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const libra::Quaternion& q_b2c, const GeomagneticField* magnet); + const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); /** * @fn ~MagSensor * @brief Destructor diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index bbb9ded4c..76ac30113 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -10,13 +10,13 @@ #include #include -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const Quaternion& q_b2c, +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), q_c2b_(q_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), @@ -29,13 +29,13 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con } } -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Quaternion& q_b2c, +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), q_c2b_(q_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 1ef457071..319f9de53 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -30,7 +30,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] id : Actuator ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] scale_facter: Scale factor matrix * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] * @param [in] min_c : Minimum magnetic moment in the component frame [Am2] @@ -41,7 +41,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, + MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); @@ -52,7 +52,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id : Actuator ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] scale_facter: Scale factor matrix * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] * @param [in] min_c : Minimum magnetic moment in the component frame [Am2] @@ -63,7 +63,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, + MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 46cb37385..dd4806f75 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -18,7 +18,7 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int id, double step_width, double dt_main_routine, - double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion q_b2c, + double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, @@ -28,7 +28,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), pos_b_(pos_b), step_width_(step_width), dead_time_(dead_time), @@ -37,8 +37,8 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera drive_flag_(drive_flag), dt_main_routine_(dt_main_routine), ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), - rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, q_b2c, structural_resonance_freq, damping_factor, - bandwidth, considers_structural_resonance), + rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, quaternion_b2c, structural_resonance_freq, + damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { Initialize(); @@ -46,7 +46,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, - libra::Quaternion q_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, + libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, @@ -56,7 +56,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), pos_b_(pos_b), step_width_(step_width), dead_time_(dead_time), @@ -65,8 +65,8 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera drive_flag_(drive_flag), dt_main_routine_(dt_main_routine), ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), - rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, q_b2c, structural_resonance_freq, damping_factor, - bandwidth, considers_structural_resonance), + rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, quaternion_b2c, structural_resonance_freq, + damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { Initialize(); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 0d759c1fe..feea7b82e 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -38,7 +38,7 @@ class RWModel : public Component, public ILoggable { * @param [in] inertia: Moment of inertia of the RW [kgm2] * @param [in] max_torque: Maximum output torque [Nm] * @param [in] max_velocity_rpm: Maximum output angular velocity [RPM] - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] pos_b: Position of RW on the body fixed frame [m] * @param [in] dead_time: Dead time of torque output [sec] * @param [in] driving_lag_coef: Driving lag coefficients @@ -56,7 +56,7 @@ class RWModel : public Component, public ILoggable { */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, + const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, @@ -75,7 +75,7 @@ class RWModel : public Component, public ILoggable { * @param [in] inertia: Moment of inertia of the RW [kgm2] * @param [in] max_torque: Maximum output torque [Nm] * @param [in] max_velocity_rpm: Maximum output angular velocity [RPM] - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] pos_b: Position of RW on the body fixed frame [m] * @param [in] dead_time: Dead time of torque output [sec] * @param [in] driving_lag_coef: Driving lag coefficients @@ -91,9 +91,9 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, const double step_width, - const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const libra::Quaternion q_b2c, const libra::Vector<3> pos_b, const double dead_time, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, + const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, + const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 6fa23f5f4..8395f98e3 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -9,12 +9,12 @@ #include RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - const double jitter_update_interval, const libra::Quaternion q_b2c, const double structural_resonance_freq, + const double jitter_update_interval, const libra::Quaternion quaternion_b2c, const double structural_resonance_freq, const double damping_factor, const double bandwidth, const bool considers_structural_resonance) : radial_force_harmonics_coef_(radial_force_harmonics_coef), radial_torque_harmonics_coef_(radial_torque_harmonics_coef), jitter_update_interval_(jitter_update_interval), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), structural_resonance_freq_(structural_resonance_freq), structural_resonance_angular_freq_(libra::tau * structural_resonance_freq), damping_factor_(damping_factor), diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 9b6694c6c..1109c6ca2 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -23,15 +23,15 @@ class RWJitter { * @param [in] radial_force_harmonics_coef: Coefficients for radial force harmonics * @param [in] radial_torque_harmonics_coef: Coefficients for radial torque harmonics * @param [in] jitter_update_interval: Jitter update interval [sec] - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] structural_resonance_freq: Frequency of structural resonance [Hz] * @param [in] damping_factor: Damping factor of structural resonance * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance */ RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - const double jitter_update_interval, const libra::Quaternion q_b2c, const double structural_resonance_freq, const double damping_factor, - const double bandwidth, const bool considers_structural_resonance); + const double jitter_update_interval, const libra::Quaternion quaternion_b2c, const double structural_resonance_freq, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance); /** * @fn ~RWJitter * @brief Destructor diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 1cfcc083e..c25d17ff3 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -15,13 +15,13 @@ using namespace std; using namespace libra; -STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, +STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), @@ -38,13 +38,13 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, con local_env_(local_env) { Initialize(); } -STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, +STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index f31f6dcff..58cb64712 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -30,7 +30,7 @@ class STT : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] * @param [in] step_time: Step time for delay calculation [sec] @@ -43,7 +43,7 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, + STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); @@ -54,7 +54,7 @@ class STT : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] * @param [in] step_time: Step time for delay calculation [sec] @@ -67,8 +67,8 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, const double sigma_ortho, - const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, + STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, + const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index ade3471e9..dc2946f61 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -13,12 +13,13 @@ using libra::NormalRand; using namespace std; -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, - const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, + const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, + const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), @@ -26,13 +27,13 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const Initialize(nr_stddev_c, nr_bias_stddev_c); } -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, - const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, - const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, + const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index bbc1b6c3e..d53984703 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -27,7 +27,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] @@ -35,9 +35,10 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& q_b2c, const double detectable_angle_rad, - const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); + SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, + const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, + const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const LocalCelestialInformation* local_celes_info); /** * @fn SunSensor * @brief Constructor with power port @@ -45,7 +46,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] id: Sensor ID - * @param [in] q_b2c: Quaternion from body frame to component frame + * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] @@ -53,7 +54,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& q_b2c, + SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index bb3d3c202..089eb0359 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -8,10 +8,10 @@ #include #include -Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, +Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) : id_(id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { - q_b2c_ = q_b2c; + q_b2c_ = quaternion_b2c; // Parameters tx_output_power_W_ = tx_params[0]; @@ -41,11 +41,11 @@ Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_tra } } -Antenna::Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, +Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, const AntennaParameters rx_params) : id_(id), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency), diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 753bb662f..45043a272 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -47,21 +47,21 @@ class Antenna { * @brief Constructor * @note TODO: This constructor will be removed. * @param [in] id: Antenna ID - * @param [in] q_b2c: Coordinate transform from body to component + * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not * @param [in] frequency: Center Frequency [MHz] * @param [in] tx_params: output, gain, loss_feeder, loss_pointing for TX * @param [in] rx_params: gain, loss_feeder, loss_pointing, system_temperature for RX */ - Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, + Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params); /** * @fn Antenna * @brief Constructor * @param [in] id: Antenna ID - * @param [in] q_b2c: Coordinate transform from body to component + * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not * @param [in] frequency: Center Frequency [MHz] @@ -70,7 +70,7 @@ class Antenna { * @param [in] rx_system_noise_temperature_K: Receive system noise temperature [K] * @param [in] rx_params: RX antenna parameters */ - Antenna(const int id, const libra::Quaternion& q_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, + Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, const AntennaParameters rx_params); /** diff --git a/src/components/real/communication/initialize_antenna.cpp b/src/components/real/communication/initialize_antenna.cpp index f65d468ed..e696771e6 100644 --- a/src/components/real/communication/initialize_antenna.cpp +++ b/src/components/real/communication/initialize_antenna.cpp @@ -23,8 +23,8 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { char Section[30] = "ANTENNA_"; strcat(Section, cs); - Quaternion q_b2c; - antenna_conf.ReadQuaternion(Section, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + antenna_conf.ReadQuaternion(Section, "quaternion_b2c", quaternion_b2c); bool is_transmitter = antenna_conf.ReadBoolean(Section, "is_transmitter"); bool is_receiver = antenna_conf.ReadBoolean(Section, "is_receiver"); @@ -72,6 +72,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { rx_params.antenna_gain_model = AntennaGainModel::ISOTROPIC; } - Antenna antenna(antenna_id, q_b2c, is_transmitter, is_receiver, frequency, tx_output_power_W, tx_params, rx_system_noise_temperature_K, rx_params); + Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency, tx_output_power_W, tx_params, rx_system_noise_temperature_K, + rx_params); return antenna; } diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index b5f1b07ba..022918502 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -28,8 +28,8 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st strcat(TelescopeSection, cs); #endif - Quaternion q_b2c; - Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", q_b2c); + Quaternion quaternion_b2c; + Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", quaternion_b2c); double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * pi / 180; // deg to rad @@ -48,7 +48,7 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); - Telescope telescope(clock_generator, q_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, + Telescope telescope(clock_generator, quaternion_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); return telescope; } diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index d117eb0d4..fd99fea39 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -11,12 +11,12 @@ using namespace std; using namespace libra; -Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, +Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info) : Component(1, clock_generator), - q_b2c_(q_b2c), + q_b2c_(quaternion_b2c), sun_forbidden_angle_(sun_forbidden_angle), earth_forbidden_angle_(earth_forbidden_angle), moon_forbidden_angle_(moon_forbidden_angle), diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 32601ca6b..dc158b3d1 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -30,7 +30,7 @@ struct Star { */ class Telescope : public Component, public ILoggable { public: - Telescope(ClockGenerator* clock_generator, libra::Quaternion& q_b2c, double sun_forbidden_angle, double earth_forbidden_angle, + Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); From 1631b310943e5976854980dbf5f3ccbffcdae5c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:27:58 +0100 Subject: [PATCH 0778/1086] Fix private variables name --- src/components/real/aocs/gnss_receiver.cpp | 90 +++++++++---------- src/components/real/aocs/gnss_receiver.hpp | 48 +++++----- src/components/real/aocs/gyro_sensor.cpp | 12 ++- src/components/real/aocs/gyro_sensor.hpp | 6 +- src/components/real/aocs/magnetometer.cpp | 6 +- src/components/real/aocs/magnetometer.hpp | 6 +- src/components/real/aocs/magnetorquer.cpp | 8 +- src/components/real/aocs/magnetorquer.hpp | 26 +++--- src/components/real/aocs/reaction_wheel.cpp | 6 +- src/components/real/aocs/reaction_wheel.hpp | 16 ++-- .../real/aocs/reaction_wheel_jitter.cpp | 10 +-- .../real/aocs/reaction_wheel_jitter.hpp | 2 +- src/components/real/aocs/star_sensor.cpp | 12 +-- src/components/real/aocs/star_sensor.hpp | 2 +- src/components/real/aocs/sun_sensor.cpp | 6 +- src/components/real/aocs/sun_sensor.hpp | 4 +- src/components/real/communication/antenna.cpp | 4 +- src/components/real/communication/antenna.hpp | 12 +-- src/components/real/mission/telescope.cpp | 14 +-- src/components/real/mission/telescope.hpp | 4 +- 20 files changed, 149 insertions(+), 145 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 0e27871b6..a0a93b471 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -15,36 +15,36 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator), id_(id), - ch_max_(ch_max), - antenna_position_b_(antenna_posision_b_m), - q_b2c_(quaternion_b2c), + max_channel_(ch_max), + antenna_position_b_m_(antenna_posision_b_m), + quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), - half_width_(half_width_rad), + half_width_rad_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), dynamics_(dynamics), gnss_satellites_(gnss_satellites), - simtime_(simulation_time) {} + simulation_time_(simulation_time) {} GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator, power_port), id_(id), - ch_max_(ch_max), - antenna_position_b_(antenna_posision_b_m), - q_b2c_(quaternion_b2c), + max_channel_(ch_max), + antenna_position_b_m_(antenna_posision_b_m), + quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), - half_width_(half_width_rad), + half_width_rad_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), dynamics_(dynamics), gnss_satellites_(gnss_satellites), - simtime_(simulation_time) {} + simulation_time_(simulation_time) {} void GNSSReceiver::MainRoutine(int count) { UNUSED(count); @@ -54,19 +54,19 @@ void GNSSReceiver::MainRoutine(int count) { CheckAntenna(pos_true_eci_, q_i2b); - if (is_gnss_sats_visible_ == 1) { // Antenna of GNSS-R can detect GNSS signal - position_ecef_ = dynamics_->GetOrbit().GetPosition_ecef_m(); + if (is_gnss_visible_ == 1) { // Antenna of GNSS-R can detect GNSS signal + position_ecef_m_ = dynamics_->GetOrbit().GetPosition_ecef_m(); position_llh_ = dynamics_->GetOrbit().GetLatLonAlt(); - velocity_ecef_ = dynamics_->GetOrbit().GetVelocity_ecef_m_s(); - AddNoise(pos_true_eci_, position_ecef_); + velocity_ecef_m_s_ = dynamics_->GetOrbit().GetVelocity_ecef_m_s(); + AddNoise(pos_true_eci_, position_ecef_m_); - utc_ = simtime_->GetCurrentUtc(); - ConvertJulianDayToGPSTime(simtime_->GetCurrentTime_jd()); + utc_ = simulation_time_->GetCurrentUtc(); + ConvertJulianDayToGPSTime(simulation_time_->GetCurrentTime_jd()); } else { // position information will not be updated in this case // only time information will be updated in this case (according to the receiver's internal clock) - utc_ = simtime_->GetCurrentUtc(); - ConvertJulianDayToGPSTime(simtime_->GetCurrentTime_jd()); + utc_ = simulation_time_->GetCurrentUtc(); + ConvertJulianDayToGPSTime(simulation_time_->GetCurrentTime_jd()); } } @@ -83,32 +83,32 @@ void GNSSReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libr // antenna normal vector at inertial frame libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - libra::Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + libra::Vector<3> antenna_direction_b = quaternion_b2c_.InverseFrameConversion(antenna_direction_c); libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); double inner = InnerProduct(pos_true_eci_, antenna_direction_i); if (inner <= 0) - is_gnss_sats_visible_ = 0; + is_gnss_visible_ = 0; else - is_gnss_sats_visible_ = 1; + is_gnss_visible_ = 1; } void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { // Cone model libra::Vector<3> gnss_sat_pos_i, ant_pos_i, ant2gnss_i, ant2gnss_i_n, sat2ant_i; - vec_gnssinfo_.clear(); + gnss_information_list_.clear(); // antenna normal vector at inertial frame libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; - libra::Vector<3> antenna_direction_b = q_b2c_.InverseFrameConversion(antenna_direction_c); + libra::Vector<3> antenna_direction_b = quaternion_b2c_.InverseFrameConversion(antenna_direction_c); libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); - sat2ant_i = q_i2b.InverseFrameConversion(antenna_position_b_); + sat2ant_i = q_i2b.InverseFrameConversion(antenna_position_b_m_); ant_pos_i = pos_true_eci_ + sat2ant_i; // initialize - gnss_sats_visible_num_ = 0; + visible_satellite_number_ = 0; int gnss_num = gnss_satellites_->GetNumOfSatellites(); @@ -140,43 +140,43 @@ void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: } double inner2 = InnerProduct(antenna_direction_i, ant2gnss_i_n); - if (inner2 > cos(half_width_ * libra::deg_to_rad) && is_visible_ant2gnss) { + if (inner2 > cos(half_width_rad_ * libra::deg_to_rad) && is_visible_ant2gnss) { // is visible - gnss_sats_visible_num_++; + visible_satellite_number_++; SetGnssInfo(ant2gnss_i, q_i2b, id_tmp); } } - if (gnss_sats_visible_num_ > 0) - is_gnss_sats_visible_ = 1; + if (visible_satellite_number_ > 0) + is_gnss_visible_ = 1; else - is_gnss_sats_visible_ = 0; + is_gnss_visible_ = 0; } void GNSSReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_i2b, std::string gnss_id) { libra::Vector<3> ant2gnss_b, ant2gnss_c; ant2gnss_b = q_i2b.FrameConversion(ant2gnss_i); - ant2gnss_c = q_b2c_.FrameConversion(ant2gnss_b); + ant2gnss_c = quaternion_b2c_.FrameConversion(ant2gnss_b); double dist = CalcNorm(ant2gnss_c); double lon = AcTan(ant2gnss_c[1], ant2gnss_c[0]); double lat = AcTan(ant2gnss_c[2], sqrt(pow(ant2gnss_c[0], 2.0) + pow(ant2gnss_c[1], 2.0))); GnssInfo gnss_info_new = {gnss_id, lat, lon, dist}; - vec_gnssinfo_.push_back(gnss_info_new); + gnss_information_list_.push_back(gnss_info_new); } void GNSSReceiver::AddNoise(libra::Vector<3> location_true_eci, libra::Vector<3> location_true_ecef) { // Simplest noise model - position_eci_[0] = location_true_eci[0] + nrs_eci_x_; - position_eci_[1] = location_true_eci[1] + nrs_eci_y_; - position_eci_[2] = location_true_eci[2] + nrs_eci_z_; + position_eci_m_[0] = location_true_eci[0] + nrs_eci_x_; + position_eci_m_[1] = location_true_eci[1] + nrs_eci_y_; + position_eci_m_[2] = location_true_eci[2] + nrs_eci_z_; // FIXME: noise in ECI frame is added to ECEF frame value - position_ecef_[0] = location_true_ecef[0] + nrs_eci_x_; - position_ecef_[1] = location_true_ecef[1] + nrs_eci_y_; - position_ecef_[2] = location_true_ecef[2] + nrs_eci_z_; + position_ecef_m_[0] = location_true_ecef[0] + nrs_eci_x_; + position_ecef_m_[1] = location_true_ecef[1] + nrs_eci_y_; + position_ecef_m_[2] = location_true_ecef[2] + nrs_eci_z_; } void GNSSReceiver::ConvertJulianDayToGPSTime(const double JulianDay) { @@ -186,10 +186,10 @@ void GNSSReceiver::ConvertJulianDayToGPSTime(const double JulianDay) { const double kSecInDay = 86400.0; // compute ToW from current JulianDay - // note:"gpstime_week_" computed in this method is larger than 1024 + // note:"gps_time_week_ " computed in this method is larger than 1024 double elapsed_day = JulianDay - kJulianDayAtGPSTimeZero; - gpstime_week_ = (unsigned int)(elapsed_day / kDayInWeek); - gpstime_sec_ = (elapsed_day - (double)(gpstime_week_)*kDayInWeek) * kSecInDay; + gps_time_week_ = (unsigned int)(elapsed_day / kDayInWeek); + gps_time_s_ = (elapsed_day - (double)(gps_time_week_)*kDayInWeek) * kSecInDay; } std::string GNSSReceiver::GetLogHeader() const // For logs @@ -224,13 +224,13 @@ std::string GNSSReceiver::GetLogValue() const // For logs str_tmp += WriteScalar(utc_.hour); str_tmp += WriteScalar(utc_.minute); str_tmp += WriteScalar(utc_.second); - str_tmp += WriteVector(position_eci_, 10); - str_tmp += WriteVector(velocity_ecef_, 10); + str_tmp += WriteVector(position_eci_m_, 10); + str_tmp += WriteVector(velocity_ecef_m_s_, 10); str_tmp += WriteScalar(position_llh_[0], 10); str_tmp += WriteScalar(position_llh_[1], 10); str_tmp += WriteScalar(position_llh_[2], 10); - str_tmp += WriteScalar(is_gnss_sats_visible_); - str_tmp += WriteScalar(gnss_sats_visible_num_); + str_tmp += WriteScalar(is_gnss_visible_); + str_tmp += WriteScalar(visible_satellite_number_); return str_tmp; } diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index cebe64ca2..8bd82b8d5 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -97,17 +97,17 @@ class GNSSReceiver : public Component, public ILoggable { * @brief Return GNSS satellite information * @param [in] ch: Channel number */ - inline const GnssInfo GetGnssInfo(int ch) const { return vec_gnssinfo_[ch]; }; + inline const GnssInfo GetGnssInfo(int ch) const { return gnss_information_list_[ch]; }; /** * @fn GetPositionECI * @brief Return Observed position in the ECI frame [m] */ - inline const libra::Vector<3> GetPositionECI(void) const { return position_eci_; } + inline const libra::Vector<3> GetPositionECI(void) const { return position_eci_m_; } /** * @fn GetPositionECEF * @brief Return Observed position in the ECEF frame [m] */ - inline const libra::Vector<3> GetPositionECEF(void) const { return position_ecef_; } + inline const libra::Vector<3> GetPositionECEF(void) const { return position_ecef_m_; } /** * @fn GetPositionLLH * @brief Return Observed position in the LLH frame [m] @@ -117,12 +117,12 @@ class GNSSReceiver : public Component, public ILoggable { * @fn GetVelocityECI * @brief Return Observed velocity in the ECI frame [m/s] */ - inline const libra::Vector<3> GetVelocityECI(void) const { return velocity_eci_; } + inline const libra::Vector<3> GetVelocityECI(void) const { return velocity_eci_m_s_; } /** * @fn GetVelocityECEF * @brief Return Observed velocity in the ECEF frame [m/s] */ - inline const libra::Vector<3> GetVelocityECEF(void) const { return velocity_ecef_; } + inline const libra::Vector<3> GetVelocityECEF(void) const { return velocity_ecef_m_s_; } // Override ILoggable /** @@ -138,34 +138,34 @@ class GNSSReceiver : public Component, public ILoggable { protected: // Parameters for receiver - const int id_; //!< Receiver ID - const int ch_max_; //!< Maximum number of channels - libra::Vector<3> antenna_position_b_; //!< GNSS antenna position at the body-fixed frame [m] - libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame (antenna frame) + const int id_; //!< Receiver ID + const int max_channel_; //!< Maximum number of channels + libra::Vector<3> antenna_position_b_m_; //!< GNSS antenna position at the body-fixed frame [m] + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (antenna frame) libra::NormalRand nrs_eci_x_, nrs_eci_y_, nrs_eci_z_; //!< Random noise for each axis - double half_width_ = 0.0; //!< Half width of the antenna cone model [rad] - std::string gnss_id_; //!< GNSS satellite number defined by GNSS system - AntennaModel antenna_model_; //!< Antenna model + double half_width_rad_ = 0.0; //!< Half width of the antenna cone model [rad] + std::string gnss_id_; //!< GNSS satellite number defined by GNSS system + AntennaModel antenna_model_; //!< Antenna model // Calculated values - libra::Vector<3> position_eci_{0.0}; //!< Observed position in the ECI frame [m] - libra::Vector<3> velocity_eci_{0.0}; //!< Observed velocity in the ECI frame [m/s] - libra::Vector<3> position_ecef_{0.0}; //!< Observed position in the ECEF frame [m] - libra::Vector<3> velocity_ecef_{0.0}; //!< Observed velocity in the ECEF frame [m/s] - libra::Vector<3> position_llh_{0.0}; //!< Observed position in the geodetic frame [rad,rad,m] TODO: use GeodeticPosition class - UTC utc_ = {2000, 1, 1, 0, 0, 0.0}; //!< Observed time in UTC [year, month, day, hour, min, sec] - unsigned int gpstime_week_ = 0; //!< Observed GPS time week part - double gpstime_sec_ = 0.0; //!< Observed GPS time second part - int is_gnss_sats_visible_ = 0; //!< Flag for GNSS satellite is visible or not - int gnss_sats_visible_num_ = 0; //!< Number of visible GNSS satellites - std::vector vec_gnssinfo_; //!< Information List of visible GNSS satellites + libra::Vector<3> position_eci_m_{0.0}; //!< Observed position in the ECI frame [m] + libra::Vector<3> velocity_eci_m_s_{0.0}; //!< Observed velocity in the ECI frame [m/s] + libra::Vector<3> position_ecef_m_{0.0}; //!< Observed position in the ECEF frame [m] + libra::Vector<3> velocity_ecef_m_s_{0.0}; //!< Observed velocity in the ECEF frame [m/s] + libra::Vector<3> position_llh_{0.0}; //!< Observed position in the geodetic frame [rad,rad,m] TODO: use GeodeticPosition class + UTC utc_ = {2000, 1, 1, 0, 0, 0.0}; //!< Observed time in UTC [year, month, day, hour, min, sec] + unsigned int gps_time_week_ = 0; //!< Observed GPS time week part + double gps_time_s_ = 0.0; //!< Observed GPS time second part + int is_gnss_visible_ = 0; //!< Flag for GNSS satellite is visible or not + int visible_satellite_number_ = 0; //!< Number of visible GNSS satellites + std::vector gnss_information_list_; //!< Information List of visible GNSS satellites // References const Dynamics* dynamics_; //!< Dynamics of spacecraft const GnssSatellites* gnss_satellites_; //!< Information of GNSS satellites - const SimulationTime* simtime_; //!< Simulation time + const SimulationTime* simulation_time_; //!< Simulation time // Internal Functions /** diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index 6d01aff1d..ec8f7f626 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -7,19 +7,23 @@ Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) - : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), dynamics_(dynamics) {} + : Component(prescaler, clock_generator, power_port), + Sensor(sensor_base), + sensor_id_(sensor_id), + quaternion_b2c_(quaternion_b2c), + dynamics_(dynamics) {} Gyro::~Gyro() {} void Gyro::MainRoutine(int count) { UNUSED(count); - omega_c_ = q_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame - omega_c_ = Measure(omega_c_); // Add noises + omega_c_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame + omega_c_ = Measure(omega_c_); // Add noises } std::string Gyro::GetLogHeader() const { diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index ca62382d0..e0538f15f 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -78,9 +78,9 @@ class Gyro : public Component, public Sensor, public ILoggable { inline const libra::Vector& GetOmegaC(void) const { return omega_c_; } protected: - libra::Vector omega_c_{0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] - int sensor_id_ = 0; //!< Sensor ID - libra::Quaternion q_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Vector omega_c_{0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] + int sensor_id_ = 0; //!< Sensor ID + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const Dynamics* dynamics_; //!< Dynamics information }; diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 11ef902c9..fe9d63413 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -8,16 +8,16 @@ MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), magnet_(magnet) {} + : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), magnet_(magnet) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), q_b2c_(quaternion_b2c), magnet_(magnet) {} + : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = q_b2c_.FrameConversion(magnet_->GetGeomagneticField_b_nT()); // Convert frame + mag_c_ = quaternion_b2c_.FrameConversion(magnet_->GetGeomagneticField_b_nT()); // Convert frame mag_c_ = Measure(mag_c_); // Add noises } diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 2a8c22302..27c289a5a 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -78,9 +78,9 @@ class MagSensor : public Component, public Sensor, public ILoggable { inline const libra::Vector& GetMagC(void) const { return mag_c_; } protected: - libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] - int sensor_id_ = 0; //!< Sensor ID - libra::Quaternion q_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] + int sensor_id_ = 0; //!< Sensor ID + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const GeomagneticField* magnet_; //!< Geomagnetic environment }; diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 76ac30113..329d9f49a 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -16,8 +16,8 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator), id_(id), - q_b2c_(quaternion_b2c), - q_c2b_(q_b2c_.Conjugate()), + quaternion_b2c_(quaternion_b2c), + q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), min_c_(min_c), @@ -35,8 +35,8 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, Pow const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(quaternion_b2c), - q_c2b_(q_b2c_.Conjugate()), + quaternion_b2c_(quaternion_b2c), + q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), max_c_(max_c), min_c_(min_c), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 319f9de53..d509c43da 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -110,19 +110,19 @@ class MagTorquer : public Component, public ILoggable { inline void SetMagMomentC(const libra::Vector mag_moment_c) { mag_moment_c_ = mag_moment_c; }; protected: - const int id_ = 0; //!< Actuator ID - const double knT2T = 1.0e-9; //!< Constant to convert nT to T - libra::Vector torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] - libra::Vector mag_moment_c_{0.0}; //!< Output output magnetic moment in the component frame [Am2] - libra::Vector mag_moment_b_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] - libra::Quaternion q_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame - libra::Quaternion q_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame - libra::Matrix scale_factor_; //!< Scale factor matrix - libra::Vector max_c_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] - libra::Vector min_c_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] - libra::Vector bias_c_{0.0}; //!< Constant bias noise in the component frame [Am2] - RandomWalk n_rw_c_; //!< Random walk noise - libra::NormalRand nrs_c_[kMtqDim]; //!< Normal random noise + const int id_ = 0; //!< Actuator ID + const double knT2T = 1.0e-9; //!< Constant to convert nT to T + libra::Vector torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] + libra::Vector mag_moment_c_{0.0}; //!< Output output magnetic moment in the component frame [Am2] + libra::Vector mag_moment_b_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Quaternion q_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame + libra::Matrix scale_factor_; //!< Scale factor matrix + libra::Vector max_c_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] + libra::Vector min_c_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] + libra::Vector bias_c_{0.0}; //!< Constant bias noise in the component frame [Am2] + RandomWalk n_rw_c_; //!< Random walk noise + libra::NormalRand nrs_c_[kMtqDim]; //!< Normal random noise const GeomagneticField* mag_env_; //!< Geomagnetic environment diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index dd4806f75..d378ff28b 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -28,7 +28,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), pos_b_(pos_b), step_width_(step_width), dead_time_(dead_time), @@ -56,7 +56,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), pos_b_(pos_b), step_width_(step_width), dead_time_(dead_time), @@ -75,7 +75,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera void RWModel::Initialize() { direction_c_ = libra::Vector<3>(0.0); direction_c_[2] = 1.0; - direction_b_ = q_b2c_.InverseFrameConversion(direction_c_); + direction_b_ = quaternion_b2c_.InverseFrameConversion(direction_c_); velocity_limit_rpm_ = max_velocity_rpm_; output_torque_b_ = libra::Vector<3>(0.0); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index feea7b82e..fe185b4b9 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -184,14 +184,14 @@ class RWModel : public Component, public ILoggable { protected: // Fixed Parameters - const int id_; //!< Actuator ID - const double inertia_; //!< Inertia of RW rotor [kgm2] - const double max_torque_; //!< Maximum output torque [Nm] - const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] - libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame - const libra::Vector<3> pos_b_; //!< Position of RW in the body fixed frame [m] - libra::Vector<3> direction_c_; //!< Wheel rotation axis on the component frame. Constant as (0 0 1). (Output torque is minus direction) - libra::Vector<3> direction_b_; //!< Wheel rotation vector in the body fixed frame. + const int id_; //!< Actuator ID + const double inertia_; //!< Inertia of RW rotor [kgm2] + const double max_torque_; //!< Maximum output torque [Nm] + const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame + const libra::Vector<3> pos_b_; //!< Position of RW in the body fixed frame [m] + libra::Vector<3> direction_c_; //!< Wheel rotation axis on the component frame. Constant as (0 0 1). (Output torque is minus direction) + libra::Vector<3> direction_b_; //!< Wheel rotation vector in the body fixed frame. // Fixed Parameters for control delay const double step_width_; //!< step width for RwOde [sec] diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 8395f98e3..39e045cdf 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -14,7 +14,7 @@ RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, : radial_force_harmonics_coef_(radial_force_harmonics_coef), radial_torque_harmonics_coef_(radial_torque_harmonics_coef), jitter_update_interval_(jitter_update_interval), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), structural_resonance_freq_(structural_resonance_freq), structural_resonance_angular_freq_(libra::tau * structural_resonance_freq), damping_factor_(damping_factor), @@ -71,11 +71,11 @@ void RWJitter::CalcJitter(double angular_velocity_rad) { // Add structural resonance if (considers_structural_resonance_) { AddStructuralResonance(); - jitter_force_b_ = q_b2c_.InverseFrameConversion(filtered_jitter_force_n_c_); - jitter_torque_b_ = q_b2c_.InverseFrameConversion(filtered_jitter_torque_n_c_); + jitter_force_b_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_force_n_c_); + jitter_torque_b_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_torque_n_c_); } else { - jitter_force_b_ = q_b2c_.InverseFrameConversion(unfiltered_jitter_force_n_c_); - jitter_torque_b_ = q_b2c_.InverseFrameConversion(unfiltered_jitter_torque_n_c_); + jitter_force_b_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_force_n_c_); + jitter_torque_b_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_torque_n_c_); } } diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 1109c6ca2..54fcca2c4 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -75,7 +75,7 @@ class RWJitter { std::vector> radial_torque_harmonics_coef_; //!< Coefficients for radial torque harmonics const double jitter_update_interval_; //!< Jitter update interval [sec] - libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame double structural_resonance_freq_; //!< Frequency of structural resonance [Hz] double structural_resonance_angular_freq_; //!< Angular Frequency of structural resonance diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index c25d17ff3..a68c6daf3 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -21,7 +21,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, con const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator), id_(id), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), @@ -44,7 +44,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_ const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), @@ -102,7 +102,7 @@ Quaternion STT::measure(const LocalCelestialInformation* local_celes_info, const void STT::update(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { Quaternion q_i2b = attinfo->GetQuaternion_i2b(); // Read true value - Quaternion q_stt_temp = q_i2b * q_b2c_; // Convert to component frame + Quaternion q_stt_temp = q_i2b * quaternion_b2c_; // Convert to component frame // Add noise on sight direction Quaternion q_sight(sight_, n_sight_); // Random noise on orthogonal direction of sight. Range [0:2pi] @@ -134,7 +134,7 @@ void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const } int STT::SunJudgement(const libra::Vector<3>& sun_b) { - Quaternion q_c2b = q_b2c_.Conjugate(); + Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); double sun_angle_rad = CalAngleVect_rad(sun_b, sight_b); if (sun_angle_rad < sun_forbidden_angle_) @@ -144,7 +144,7 @@ int STT::SunJudgement(const libra::Vector<3>& sun_b) { } int STT::EarthJudgement(const libra::Vector<3>& earth_b) { - Quaternion q_c2b = q_b2c_.Conjugate(); + Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge @@ -157,7 +157,7 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { } int STT::MoonJudgement(const libra::Vector<3>& moon_b) { - Quaternion q_c2b = q_b2c_.Conjugate(); + Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); double moon_angle_rad = CalAngleVect_rad(moon_b, sight_b); if (moon_angle_rad < moon_forbidden_angle_) diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 58cb64712..157462fa4 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -105,7 +105,7 @@ class STT : public Component, public ILoggable { protected: // STT general parameters const int id_; //!< Sensor ID - libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame libra::Quaternion q_stt_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion libra::Vector<3> sight_; //!< Sight direction vector at component frame libra::Vector<3> ortho1_; //!< The first orthogonal direction of sight at component frame diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index dc2946f61..ca46da19d 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -19,7 +19,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator), id_(id), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), @@ -33,7 +33,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator, power_port), id_(id), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), @@ -61,7 +61,7 @@ void SunSensor::measure() { libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = Normalize(sun_pos_b); - sun_c_ = q_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component + sun_c_ = quaternion_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component SunDetectionJudgement(); // Judge the sun is inside the FoV diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index d53984703..fb3b6709d 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -81,14 +81,14 @@ class SunSensor : public Component, public ILoggable { // Getter inline bool GetSunDetectedFlag() const { return sun_detected_flag_; }; inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_c_; }; - inline const libra::Vector<3> GetMeasuredSun_b() const { return q_b2c_.Conjugate().FrameConversion(measured_sun_c_); }; + inline const libra::Vector<3> GetMeasuredSun_b() const { return quaternion_b2c_.Conjugate().FrameConversion(measured_sun_c_); }; inline double GetSunAngleAlpha() const { return alpha_; }; inline double GetSunAngleBeta() const { return beta_; }; inline double GetSolarIlluminance() const { return solar_illuminance_; }; protected: const int id_; //!< Sensor ID - libra::Quaternion q_b2c_; //!< Quaternion from body frame to component frame (Z-axis of the component is sight direction) + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (Z-axis of the component is sight direction) double intensity_lower_threshold_percent_; //!< If the light intensity becomes smaller than this, it becomes impossible to get the sun direction libra::Vector<3> sun_c_{0.0}; //!< True value of sun vector in the component frame diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 089eb0359..dee2786de 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -11,7 +11,7 @@ Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) : id_(id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { - q_b2c_ = quaternion_b2c; + quaternion_b2c_ = quaternion_b2c; // Parameters tx_output_power_W_ = tx_params[0]; @@ -45,7 +45,7 @@ Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bo const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, const AntennaParameters rx_params) : id_(id), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency), diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 45043a272..3e3b5b43d 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -106,7 +106,7 @@ class Antenna { * @fn GetQuaternion_b2c * @brief Return quaternion from body to component */ - inline Quaternion GetQuaternion_b2c() const { return q_b2c_; } + inline Quaternion GetQuaternion_b2c() const { return quaternion_b2c_; } /** * @fn IsTransmitter @@ -121,11 +121,11 @@ class Antenna { protected: // General info - int id_; //!< Antenna ID - Quaternion q_b2c_; //!< Coordinate transform from body to component - bool is_transmitter_; //!< Antenna for transmitter or not - bool is_receiver_; //!< Antenna for receiver or not - double frequency_; //!< Center Frequency [MHz] + int id_; //!< Antenna ID + Quaternion quaternion_b2c_; //!< Coordinate transform from body to component + bool is_transmitter_; //!< Antenna for transmitter or not + bool is_receiver_; //!< Antenna for receiver or not + double frequency_; //!< Center Frequency [MHz] // Tx info double tx_output_power_W_; //!< Transmit output power [W] diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index fd99fea39..7388a8078 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -16,7 +16,7 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info) : Component(1, clock_generator), - q_b2c_(quaternion_b2c), + quaternion_b2c_(quaternion_b2c), sun_forbidden_angle_(sun_forbidden_angle), earth_forbidden_angle_(earth_forbidden_angle), moon_forbidden_angle_(moon_forbidden_angle), @@ -70,9 +70,9 @@ void Telescope::MainRoutine(int count) { // No update when Hipparocos Catalogue was not readed if (hipp_->IsCalcEnabled) ObserveStars(); // Debug ****************************************************************** - // sun_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); - // earth_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); - // moon_pos_c = q_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); + // sun_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); + // earth_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); + // moon_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); // angle_sun = CalcAngleTwoVectors_rad(sight_, sun_pos_c) * 180/libra::pi; // angle_earth = CalcAngleTwoVectors_rad(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = CalcAngleTwoVectors_rad(sight_, moon_pos_c) * 180 / // libra::pi; @@ -80,7 +80,7 @@ void Telescope::MainRoutine(int count) { } bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { - Quaternion q_c2b = q_b2c_.Conjugate(); + Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_); double angle_rad = libra::CalcAngleTwoVectors_rad(target_b, sight_b); if (angle_rad < forbidden_angle) { @@ -90,7 +90,7 @@ bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const doub } void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b) { - Vector<3, double> target_c = q_b2c_.FrameConversion(target_b); + Vector<3, double> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame @@ -111,7 +111,7 @@ void Telescope::ObserveStars() { while (star_in_sight.size() < num_of_logged_stars_) { Vector<3> target_b = hipp_->GetStarDirection_b(count, q_i2b); - Vector<3> target_c = q_b2c_.FrameConversion(target_b); + Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index dc158b3d1..6751717ef 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -43,8 +43,8 @@ class Telescope : public Component, public ILoggable { protected: private: - libra::Quaternion q_b2c_; //!< Quaternion from the body frame to component frame - libra::Vector<3> sight_; //!< Sight direction vector in the component frame + libra::Quaternion quaternion_b2c_; //!< Quaternion from the body frame to component frame + libra::Vector<3> sight_; //!< Sight direction vector in the component frame double sun_forbidden_angle_; //!< Sun forbidden angle [rad] double earth_forbidden_angle_; //!< Earth forbidden angle [rad] From ba94c9c3fb5e33b9f0ca99a7b6501c90bac877c4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:32:22 +0100 Subject: [PATCH 0779/1086] Fix private variables name --- src/components/real/aocs/gnss_receiver.cpp | 6 +++--- src/components/real/aocs/gnss_receiver.hpp | 2 +- src/components/real/aocs/magnetorquer.cpp | 6 +++--- src/components/real/aocs/magnetorquer.hpp | 2 +- src/components/real/aocs/reaction_wheel.cpp | 6 +++--- src/components/real/aocs/reaction_wheel.hpp | 2 +- src/components/real/aocs/star_sensor.cpp | 6 +++--- src/components/real/aocs/star_sensor.hpp | 2 +- src/components/real/aocs/sun_sensor.cpp | 6 +++--- src/components/real/aocs/sun_sensor.hpp | 4 ++-- src/components/real/communication/antenna.cpp | 4 ++-- src/components/real/communication/antenna.hpp | 2 +- src/components/real/power/solar_array_panel.cpp | 10 +++++----- src/components/real/power/solar_array_panel.hpp | 2 +- src/components/real/propulsion/simple_thruster.cpp | 6 +++--- src/components/real/propulsion/simple_thruster.hpp | 2 +- 16 files changed, 34 insertions(+), 34 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index a0a93b471..0559c23bb 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -14,7 +14,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), max_channel_(ch_max), antenna_position_b_m_(antenna_posision_b_m), quaternion_b2c_(quaternion_b2c), @@ -32,7 +32,7 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator, power_port), - id_(id), + component_id_(id), max_channel_(ch_max), antenna_position_b_m_(antenna_posision_b_m), quaternion_b2c_(quaternion_b2c), @@ -195,7 +195,7 @@ void GNSSReceiver::ConvertJulianDayToGPSTime(const double JulianDay) { std::string GNSSReceiver::GetLogHeader() const // For logs { std::string str_tmp = ""; - const std::string sensor_id = std::to_string(static_cast(id_)); + const std::string sensor_id = std::to_string(static_cast(component_id_)); std::string sensor_name = "gnss_receiver" + sensor_id + "_"; str_tmp += WriteScalar(sensor_name + "measured_utc_time_year"); diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 8bd82b8d5..032d4497c 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -138,7 +138,7 @@ class GNSSReceiver : public Component, public ILoggable { protected: // Parameters for receiver - const int id_; //!< Receiver ID + const int component_id_; //!< Receiver ID const int max_channel_; //!< Maximum number of channels libra::Vector<3> antenna_position_b_m_; //!< GNSS antenna position at the body-fixed frame [m] libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (antenna frame) diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 329d9f49a..7788f5ee4 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -15,7 +15,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), @@ -34,7 +34,7 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, Pow const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator, power_port), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), @@ -83,7 +83,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { std::string MagTorquer::GetLogHeader() const { std::string str_tmp = ""; - const std::string actuator_id = std::to_string(static_cast(id_)); + const std::string actuator_id = std::to_string(static_cast(component_id_)); std::string actuator_name = "magnetorquer" + actuator_id + "_"; str_tmp += WriteVector(actuator_name + "output_magnetic_moment", "b", "Am2", kMtqDim); diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index d509c43da..4041af2f8 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -110,7 +110,7 @@ class MagTorquer : public Component, public ILoggable { inline void SetMagMomentC(const libra::Vector mag_moment_c) { mag_moment_c_ = mag_moment_c; }; protected: - const int id_ = 0; //!< Actuator ID + const int component_id_ = 0; //!< Actuator ID const double knT2T = 1.0e-9; //!< Constant to convert nT to T libra::Vector torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] libra::Vector mag_moment_c_{0.0}; //!< Output output magnetic moment in the component frame [Am2] diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index d378ff28b..1dfdf7055 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -24,7 +24,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, fast_prescaler), - id_(id), + component_id_(id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), @@ -52,7 +52,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, power_port, fast_prescaler), - id_(id), + component_id_(id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), @@ -183,7 +183,7 @@ void RWModel::SetVelocityLimitRpm(double velocity_limit_rpm) { std::string RWModel::GetLogHeader() const { std::string str_tmp = ""; - std::string component_name = "rw" + std::to_string(static_cast(id_)) + "_"; + std::string component_name = "rw" + std::to_string(static_cast(component_id_)) + "_"; str_tmp += WriteScalar(component_name + "angular_velocity", "rad/s"); str_tmp += WriteScalar(component_name + "angular_velocity", "rpm"); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index fe185b4b9..a60484bc7 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -184,7 +184,7 @@ class RWModel : public Component, public ILoggable { protected: // Fixed Parameters - const int id_; //!< Actuator ID + const int component_id_; //!< Actuator ID const double inertia_; //!< Inertia of RW rotor [kgm2] const double max_torque_; //!< Maximum output torque [Nm] const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index a68c6daf3..04198a447 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -20,7 +20,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, con const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), @@ -43,7 +43,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_ const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator, power_port), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), @@ -176,7 +176,7 @@ int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b) { std::string STT::GetLogHeader() const { std::string str_tmp = ""; - const std::string sensor_id = std::to_string(static_cast(id_)); + const std::string sensor_id = std::to_string(static_cast(component_id_)); std::string sensor_name = "stt" + sensor_id + "_"; str_tmp += WriteQuaternion(sensor_name + "measured_quaternion", "i2c"); diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 157462fa4..26a5f0ed7 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -104,7 +104,7 @@ class STT : public Component, public ILoggable { protected: // STT general parameters - const int id_; //!< Sensor ID + const int component_id_; //!< Sensor ID libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame libra::Quaternion q_stt_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion libra::Vector<3> sight_; //!< Sight direction vector at component frame diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index ca46da19d..4a9d57541 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -18,7 +18,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), @@ -32,7 +32,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator, power_port), - id_(id), + component_id_(id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), @@ -132,7 +132,7 @@ double SunSensor::TanRange(double x) { string SunSensor::GetLogHeader() const { string str_tmp = ""; - const string sensor_id = std::to_string(static_cast(id_)); + const string sensor_id = std::to_string(static_cast(component_id_)); std::string sensor_name = "sun_sensor" + sensor_id + "_"; str_tmp += WriteVector(sensor_name + "measured_sun_direction", "c", "-", 3); diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index fb3b6709d..7d43385c9 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -87,8 +87,8 @@ class SunSensor : public Component, public ILoggable { inline double GetSolarIlluminance() const { return solar_illuminance_; }; protected: - const int id_; //!< Sensor ID - libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (Z-axis of the component is sight direction) + const int component_id_; //!< Sensor ID + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (Z-axis of the component is sight direction) double intensity_lower_threshold_percent_; //!< If the light intensity becomes smaller than this, it becomes impossible to get the sun direction libra::Vector<3> sun_c_{0.0}; //!< True value of sun vector in the component frame diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index dee2786de..b01fd1816 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -10,7 +10,7 @@ Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) - : id_(id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { + : component_id_(id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { quaternion_b2c_ = quaternion_b2c; // Parameters @@ -44,7 +44,7 @@ Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bo Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, const AntennaParameters rx_params) - : id_(id), + : component_id_(id), quaternion_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 3e3b5b43d..aeea9ea2e 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -121,7 +121,7 @@ class Antenna { protected: // General info - int id_; //!< Antenna ID + int component_id_; //!< Antenna ID Quaternion quaternion_b2c_; //!< Coordinate transform from body to component bool is_transmitter_; //!< Antenna for transmitter or not bool is_receiver_; //!< Antenna for receiver or not diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 6a4b174b4..8204f7730 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -12,7 +12,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int numbe libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), @@ -30,7 +30,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int numbe libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), @@ -47,7 +47,7 @@ SAP::SAP(ClockGenerator* clock_generator, int id, int number_of_series, int numb double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(10, clock_generator), - id_(id), + component_id_(id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), @@ -63,7 +63,7 @@ SAP::SAP(ClockGenerator* clock_generator, int id, int number_of_series, int numb SAP::SAP(const SAP& obj) : Component(obj), - id_(obj.id_), + component_id_(obj.component_id_), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), cell_area_(obj.cell_area_), @@ -85,7 +85,7 @@ void SAP::SetVoltage_V(const double voltage) { voltage_ = voltage; } std::string SAP::GetLogHeader() const { std::string str_tmp = ""; - std::string component_name = "sap" + std::to_string(id_) + "_"; + std::string component_name = "sap" + std::to_string(component_id_) + "_"; str_tmp += WriteScalar(component_name + "generated_power", "W"); return str_tmp; } diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 534514da5..e39b5fc90 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -105,7 +105,7 @@ class SAP : public Component, public ILoggable { std::string GetLogValue() const override; private: - const int id_; //!< SAP ID TODO: Use string? + const int component_id_; //!< SAP ID TODO: Use string? const int number_of_series_; //!< Number of series connected solar cells const int number_of_parallel_; //!< Number of parallel connected solar cells const double cell_area_; //!< Solar cell area [m^2] diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 0b4e7a8cc..884d629eb 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -13,7 +13,7 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), - id_(id), + component_id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), thrust_magnitude_max_(max_mag), @@ -27,7 +27,7 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), - id_(id), + component_id_(id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), thrust_magnitude_max_(max_mag), @@ -73,7 +73,7 @@ void SimpleThruster::CalcTorque(Vector<3> center) { std::string SimpleThruster::GetLogHeader() const { std::string str_tmp = ""; - std::string head = "simple_thruster" + std::to_string(id_) + "_"; + std::string head = "simple_thruster" + std::to_string(component_id_) + "_"; str_tmp += WriteVector(head + "output_thrust", "b", "N", 3); str_tmp += WriteVector(head + "output_torque", "b", "Nm", 3); str_tmp += WriteScalar(head + "output_thrust_norm", "N"); diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 5c4feebec..81556b127 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -106,7 +106,7 @@ class SimpleThruster : public Component, public ILoggable { protected: // parameters - const int id_; //!< Thruster ID + const int component_id_; //!< Thruster ID Vector<3> thruster_pos_b_{0.0}; //!< Thruster position @ body frame [m] Vector<3> thrust_dir_b_{0.0}; //!< Thrust direction @ body frame double duty_ = 0.0; //!< PWM Duty [0.0 : 1.0] From 6c454e4e744a34e33425165a7c66b5d8e6ed7f6d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:44:26 +0100 Subject: [PATCH 0780/1086] Rename GNSSReceiver to GnssReceiver --- src/components/real/aocs/gnss_receiver.cpp | 68 +++++++++---------- src/components/real/aocs/gnss_receiver.hpp | 68 +++++++++---------- .../real/aocs/initialize_gnss_receiver.cpp | 26 +++---- .../real/aocs/initialize_gnss_receiver.hpp | 14 ++-- src/components/real/aocs/magnetorquer.cpp | 15 ++-- src/components/real/aocs/magnetorquer.hpp | 17 ++--- src/components/real/aocs/reaction_wheel.cpp | 19 +++--- src/components/real/aocs/reaction_wheel.hpp | 10 +-- src/components/real/aocs/star_sensor.cpp | 18 ++--- src/components/real/aocs/star_sensor.hpp | 10 +-- src/components/real/aocs/sun_sensor.cpp | 8 +-- src/components/real/aocs/sun_sensor.hpp | 10 +-- src/components/real/communication/antenna.cpp | 14 ++-- src/components/real/communication/antenna.hpp | 10 +-- src/components/real/mission/telescope.cpp | 4 +- .../real/power/solar_array_panel.cpp | 14 ++-- .../real/power/solar_array_panel.hpp | 16 ++--- .../real/propulsion/simple_thruster.cpp | 8 +-- .../real/propulsion/simple_thruster.hpp | 13 ++-- .../sample_spacecraft/sample_components.cpp | 4 +- .../sample_spacecraft/sample_components.hpp | 4 +- 21 files changed, 187 insertions(+), 183 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 0559c23bb..dfde402e2 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -9,14 +9,14 @@ #include #include -GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, +GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, const int ch_max, + const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), max_channel_(ch_max), - antenna_position_b_m_(antenna_posision_b_m), + antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), @@ -27,14 +27,14 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, dynamics_(dynamics), gnss_satellites_(gnss_satellites), simulation_time_(simulation_time) {} -GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const std::string gnss_id, - const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, +GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator, power_port), - component_id_(id), + component_id_(component_id), max_channel_(ch_max), - antenna_position_b_m_(antenna_posision_b_m), + antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), @@ -46,13 +46,13 @@ GNSSReceiver::GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, gnss_satellites_(gnss_satellites), simulation_time_(simulation_time) {} -void GNSSReceiver::MainRoutine(int count) { +void GnssReceiver::MainRoutine(int count) { UNUSED(count); libra::Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); - Quaternion q_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); + Quaternion quaternion_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); - CheckAntenna(pos_true_eci_, q_i2b); + CheckAntenna(pos_true_eci_, quaternion_i2b); if (is_gnss_visible_ == 1) { // Antenna of GNSS-R can detect GNSS signal position_ecef_m_ = dynamics_->GetOrbit().GetPosition_ecef_m(); @@ -70,21 +70,21 @@ void GNSSReceiver::MainRoutine(int count) { } } -void GNSSReceiver::CheckAntenna(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { +void GnssReceiver::CheckAntenna(const libra::Vector<3> pos_true_eci_, libra::Quaternion quaternion_i2b) { if (antenna_model_ == SIMPLE) - CheckAntennaSimple(pos_true_eci_, q_i2b); + CheckAntennaSimple(pos_true_eci_, quaternion_i2b); else if (antenna_model_ == CONE) - CheckAntennaCone(pos_true_eci_, q_i2b); + CheckAntennaCone(pos_true_eci_, quaternion_i2b); } -void GNSSReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { +void GnssReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libra::Quaternion quaternion_i2b) { // Simplest model // GNSS sats are visible when antenna directs anti-earth direction // antenna normal vector at inertial frame libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; libra::Vector<3> antenna_direction_b = quaternion_b2c_.InverseFrameConversion(antenna_direction_c); - libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); + libra::Vector<3> antenna_direction_i = quaternion_i2b.InverseFrameConversion(antenna_direction_b); double inner = InnerProduct(pos_true_eci_, antenna_direction_i); if (inner <= 0) @@ -93,7 +93,7 @@ void GNSSReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libr is_gnss_visible_ = 1; } -void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra::Quaternion q_i2b) { +void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra::Quaternion quaternion_i2b) { // Cone model libra::Vector<3> gnss_sat_pos_i, ant_pos_i, ant2gnss_i, ant2gnss_i_n, sat2ant_i; gnss_information_list_.clear(); @@ -102,9 +102,9 @@ void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: libra::Vector<3> antenna_direction_c(0.0); antenna_direction_c[2] = 1.0; libra::Vector<3> antenna_direction_b = quaternion_b2c_.InverseFrameConversion(antenna_direction_c); - libra::Vector<3> antenna_direction_i = q_i2b.InverseFrameConversion(antenna_direction_b); + libra::Vector<3> antenna_direction_i = quaternion_i2b.InverseFrameConversion(antenna_direction_b); - sat2ant_i = q_i2b.InverseFrameConversion(antenna_position_b_m_); + sat2ant_i = quaternion_i2b.InverseFrameConversion(antenna_position_b_m_); ant_pos_i = pos_true_eci_ + sat2ant_i; // initialize @@ -143,7 +143,7 @@ void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: if (inner2 > cos(half_width_rad_ * libra::deg_to_rad) && is_visible_ant2gnss) { // is visible visible_satellite_number_++; - SetGnssInfo(ant2gnss_i, q_i2b, id_tmp); + SetGnssInfo(ant2gnss_i, quaternion_i2b, id_tmp); } } @@ -153,10 +153,10 @@ void GNSSReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: is_gnss_visible_ = 0; } -void GNSSReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_i2b, std::string gnss_id) { +void GnssReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion quaternion_i2b, std::string gnss_id) { libra::Vector<3> ant2gnss_b, ant2gnss_c; - ant2gnss_b = q_i2b.FrameConversion(ant2gnss_i); + ant2gnss_b = quaternion_i2b.FrameConversion(ant2gnss_i); ant2gnss_c = quaternion_b2c_.FrameConversion(ant2gnss_b); double dist = CalcNorm(ant2gnss_c); @@ -167,32 +167,32 @@ void GNSSReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_ gnss_information_list_.push_back(gnss_info_new); } -void GNSSReceiver::AddNoise(libra::Vector<3> location_true_eci, libra::Vector<3> location_true_ecef) { +void GnssReceiver::AddNoise(libra::Vector<3> position_true_i_m, libra::Vector<3> position_true_ecef_m) { // Simplest noise model - position_eci_m_[0] = location_true_eci[0] + nrs_eci_x_; - position_eci_m_[1] = location_true_eci[1] + nrs_eci_y_; - position_eci_m_[2] = location_true_eci[2] + nrs_eci_z_; + position_eci_m_[0] = position_true_i_m[0] + nrs_eci_x_; + position_eci_m_[1] = position_true_i_m[1] + nrs_eci_y_; + position_eci_m_[2] = position_true_i_m[2] + nrs_eci_z_; // FIXME: noise in ECI frame is added to ECEF frame value - position_ecef_m_[0] = location_true_ecef[0] + nrs_eci_x_; - position_ecef_m_[1] = location_true_ecef[1] + nrs_eci_y_; - position_ecef_m_[2] = location_true_ecef[2] + nrs_eci_z_; + position_ecef_m_[0] = position_true_ecef_m[0] + nrs_eci_x_; + position_ecef_m_[1] = position_true_ecef_m[1] + nrs_eci_y_; + position_ecef_m_[2] = position_true_ecef_m[2] + nrs_eci_z_; } -void GNSSReceiver::ConvertJulianDayToGPSTime(const double JulianDay) { +void GnssReceiver::ConvertJulianDayToGPSTime(const double julian_day) { const double kJulianDayAtGPSTimeZero = 2444244.5; // corresponds to 1980/1/5 midnight const double kDayInWeek = 7.0; // const double kSecInWeek = 604800.0; const double kSecInDay = 86400.0; - // compute ToW from current JulianDay + // compute ToW from current julian_day // note:"gps_time_week_ " computed in this method is larger than 1024 - double elapsed_day = JulianDay - kJulianDayAtGPSTimeZero; + double elapsed_day = julian_day - kJulianDayAtGPSTimeZero; gps_time_week_ = (unsigned int)(elapsed_day / kDayInWeek); gps_time_s_ = (elapsed_day - (double)(gps_time_week_)*kDayInWeek) * kSecInDay; } -std::string GNSSReceiver::GetLogHeader() const // For logs +std::string GnssReceiver::GetLogHeader() const // For logs { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(component_id_)); @@ -215,7 +215,7 @@ std::string GNSSReceiver::GetLogHeader() const // For logs return str_tmp; } -std::string GNSSReceiver::GetLogValue() const // For logs +std::string GnssReceiver::GetLogValue() const // For logs { std::string str_tmp = ""; str_tmp += WriteScalar(utc_.year); diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 032d4497c..c5fc7d58e 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -28,29 +28,29 @@ enum AntennaModel { * @struct GnssInfo * @brief Information of GNSS satellites */ -typedef struct _gnssinfo { - std::string ID; //!< ID of GNSS satellites - double latitude; //!< Latitude on the antenna frame [rad] - double longitude; //!< Longitude on the antenna frame [rad] - double distance; //!< Distance between the GNSS satellite and the GNSS receiver antenna [m] +typedef struct _gnss_info { + std::string ID; //!< ID of GNSS satellites + double latitude_rad; //!< Latitude on the antenna frame [rad] + double longitude_rad; //!< Longitude on the antenna frame [rad] + double distance_m; //!< Distance between the GNSS satellite and the GNSS receiver antenna [m] } GnssInfo; /** - * @class GNSSReceiver + * @class GnssReceiver * @brief Class to emulate GNSS receiver */ -class GNSSReceiver : public Component, public ILoggable { +class GnssReceiver : public Component, public ILoggable { public: /** - * @fn GNSSReceiver + * @fn GnssReceiver * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: Component ID + * @param [in] component_id: Component ID * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels * @param [in] antenna_model: Antenna model - * @param [in] antenna_posision_b_m: GNSS antenna position at the body-fixed frame [m] + * @param [in] antenna_position_b_m: GNSS antenna position at the body-fixed frame [m] * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) * @param [in] half_width_rad: Half width of the antenna cone model [rad] * @param [in] noise_standard_deviation_m: Standard deviation of normal random noise in the ECI frame [m] @@ -58,12 +58,12 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_satellites: GNSS Satellites information * @param [in] simulation_time: Simulation time information */ - GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, const int id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, + GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, const int ch_max, + const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); /** - * @fn GNSSReceiver + * @fn GnssReceiver * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -71,7 +71,7 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_id: GNSS satellite number defined by GNSS system * @param [in] ch_max: Maximum number of channels * @param [in] antenna_model: Antenna model - * @param [in] antenna_posision_b_m: GNSS antenna position at the body-fixed frame [m] + * @param [in] antenna_position_b_m: GNSS antenna position at the body-fixed frame [m] * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) * @param [in] half_width_rad: Half width of the antenna cone model [rad] * @param [in] noise_standard_deviation_m: Standard deviation of normal random noise in the ECI frame [m] @@ -79,10 +79,10 @@ class GNSSReceiver : public Component, public ILoggable { * @param [in] gnss_satellites: GNSS Satellites information * @param [in] simulation_time: Simulation time information */ - GNSSReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> antenna_posision_b_m, const libra::Quaternion quaternion_b2c, - const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); + GnssReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, std::string gnss_id, + const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, + const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, + const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); // Override functions for Component /** @@ -172,47 +172,47 @@ class GNSSReceiver : public Component, public ILoggable { * @fn CheckAntenna * @brief Check the antenna can detect GNSS signal * @note This function just calls other check functions according to the antenna mode - * @param [in] location_true: True position of the spacecraft in the ECI frame [m] - * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame + * @param [in] position_true_i_m: True position of the spacecraft in the ECI frame [m] + * @param [in] quaternion_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntenna(libra::Vector<3> location_true, libra::Quaternion q_i2b); + void CheckAntenna(libra::Vector<3> position_true_i_m, libra::Quaternion quaternion_i2b); /** * @fn CheckAntennaSimple * @brief Check the antenna can detect GNSS signal with Simple mode * @note GNSS satellites are visible when antenna directs anti-earth direction - * @param [in] location_true: True position of the spacecraft in the ECI frame [m] - * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame + * @param [in] position_true_i_m: True position of the spacecraft in the ECI frame [m] + * @param [in] quaternion_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntennaSimple(libra::Vector<3> location_true, libra::Quaternion q_i2b); + void CheckAntennaSimple(libra::Vector<3> position_true_i_m, libra::Quaternion quaternion_i2b); /** * @fn CheckAntennaCone * @brief Check the antenna can detect GNSS signal with Cone mode * @note The visible GNSS satellites are counted by using GNSS satellite position and the antenna direction with cone antenna pattern - * @param [in] location_true: True position of the spacecraft in the ECI frame [m] - * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame + * @param [in] position_true_i_m: True position of the spacecraft in the ECI frame [m] + * @param [in] quaternion_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame */ - void CheckAntennaCone(libra::Vector<3> location_true, libra::Quaternion q_i2b); + void CheckAntennaCone(libra::Vector<3> position_true_i_m, libra::Quaternion quaternion_i2b); /** * @fn SetGnssInfo * @brief Calculate and set the GnssInfo values of target GNSS satellite * @param [in] ant2gnss_i: Position vector from the antenna to the GNSS satellites in the ECI frame - * @param [in] q_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame + * @param [in] quaternion_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame * @param [in] gnss_id: ID of target GNSS satellite */ - void SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion q_i2b, std::string gnss_id); + void SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion quaternion_i2b, std::string gnss_id); /** * @fn AddNoise * @brief Substitutional method for "Measure" in other sensor models inherited Sensor class - * @param [in] location_true_eci: True position of the spacecraft in the ECI frame [m] - * @param [in] location_true_ecef: True position of the spacecraft in the ECEF frame [m] + * @param [in] position_true_i_m: True position of the spacecraft in the ECI frame [m] + * @param [in] position_true_ecef_m: True position of the spacecraft in the ECEF frame [m] */ - void AddNoise(libra::Vector<3> location_true_eci, libra::Vector<3> location_true_ecef); + void AddNoise(libra::Vector<3> position_true_i_m, libra::Vector<3> position_true_ecef_m); /** * @fn ConvertJulianDayToGPSTime * @brief Convert Julian day to GPS time - * @param [in] JulianDay: Julian day + * @param [in] julian_day: Julian day */ - void ConvertJulianDayToGPSTime(const double JulianDay); + void ConvertJulianDayToGPSTime(const double julian_day); }; #endif // S2E_COMPONENTS_REAL_AOCS_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index 6e94ddf30..7f88bcac9 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -17,14 +17,14 @@ typedef struct _gnssrecever_param { std::string gnss_id; int ch_max; Vector<3> noise_standard_deviation_m; -} GNSSReceiverParam; +} GnssReceiverParam; -GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites, const int id) { - GNSSReceiverParam gnssreceiver_param; +GnssReceiverParam ReadGnssReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites, const int component_id) { + GnssReceiverParam gnssreceiver_param; IniAccess gnssr_conf(fname); const char* sensor_name = "GNSS_RECEIVER_"; - const std::string section_name = sensor_name + std::to_string(static_cast(id)); + const std::string section_name = sensor_name + std::to_string(static_cast(component_id)); const char* GSection = section_name.c_str(); int prescaler = gnssr_conf.ReadInt(GSection, "prescaler"); @@ -49,24 +49,24 @@ GNSSReceiverParam ReadGNSSReceiverIni(const std::string fname, const GnssSatelli return gnssreceiver_param; } -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { - GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); + GnssReceiverParam gr_param = ReadGnssReceiverIni(fname, gnss_satellites, component_id); - GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, - gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, gnss_satellites, - simulation_time); + GnssReceiver gnss_r(gr_param.prescaler, clock_generator, component_id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, + gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, + gnss_satellites, simulation_time); return gnss_r; } -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { - GNSSReceiverParam gr_param = ReadGNSSReceiverIni(fname, gnss_satellites, id); +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string fname, + const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { + GnssReceiverParam gr_param = ReadGnssReceiverIni(fname, gnss_satellites, component_id); // PowerPort power_port->InitializeWithInitializeFile(fname); - GNSSReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, + GnssReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, component_id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, gnss_satellites, simulation_time); return gnss_r; diff --git a/src/components/real/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp index 8e13e11ba..ec05b3c5b 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -9,29 +9,29 @@ #include /** - * @fn InitGNSSReceiver + * @fn InitGnssReceiver * @brief Initialize functions for GNSS Receiver without power port * @param [in] clock_generator: Clock generator - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information * @param [in] simulation_time: Simulation time information */ -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, int id, const std::string fname, const Dynamics* dynamics, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string fname, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); /** - * @fn InitGNSSReceiver + * @fn InitGnssReceiver * @brief Initialize functions for GNSS Receiver with power port * @param [in] clock_generator: Clock generator - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] power_port: Power port * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information * @param [in] simulation_time: Simulation time information */ -GNSSReceiver InitGNSSReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int id, const std::string fname, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string fname, + const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 7788f5ee4..722a0cf37 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -10,12 +10,12 @@ #include #include -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const Quaternion& quaternion_b2c, +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), @@ -29,12 +29,13 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con } } -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Quaternion& quaternion_b2c, - const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, - const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) +MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, + const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, + const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, + const GeomagneticField* mag_env) : Component(prescaler, clock_generator, power_port), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), q_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 4041af2f8..9f4d1378b 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -29,7 +29,7 @@ class MagTorquer : public Component, public ILoggable { * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id : Actuator ID + * @param [in] component_id : Actuator ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] scale_facter: Scale factor matrix * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] @@ -41,7 +41,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, + MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); @@ -51,7 +51,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] id : Actuator ID + * @param [in] component_id : Actuator ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] scale_facter: Scale factor matrix * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] @@ -63,10 +63,11 @@ class MagTorquer : public Component, public ILoggable { * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] magnet: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, - const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, - const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); + MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, + const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, + const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, + const GeomagneticField* mag_env); // Override functions for Component /** @@ -110,7 +111,7 @@ class MagTorquer : public Component, public ILoggable { inline void SetMagMomentC(const libra::Vector mag_moment_c) { mag_moment_c_ = mag_moment_c; }; protected: - const int component_id_ = 0; //!< Actuator ID + const int component_id_ = 0; //!< Actuator ID const double knT2T = 1.0e-9; //!< Constant to convert nT to T libra::Vector torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] libra::Vector mag_moment_c_{0.0}; //!< Output output magnetic moment in the component frame [Am2] diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 1dfdf7055..2b920599a 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -17,14 +17,15 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int id, double step_width, double dt_main_routine, - double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, - libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, - bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coef, - vector> radial_torque_harmonics_coef, double structural_resonance_freq, double damping_factor, double bandwidth, - bool considers_structural_resonance, bool drive_flag, double init_velocity) +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int component_id, double step_width, + double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, + libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, + libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, + vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, + double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, + double init_velocity) : Component(prescaler, clock_generator, fast_prescaler), - component_id_(id), + component_id_(component_id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), @@ -44,7 +45,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, double step_width, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, double step_width, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -52,7 +53,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, power_port, fast_prescaler), - component_id_(id), + component_id_(component_id), inertia_(inertia), max_torque_(max_torque), max_velocity_rpm_(max_velocity_rpm), diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index a60484bc7..e16318664 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -31,7 +31,7 @@ class RWModel : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] fast_prescaler: Frequency scale factor for fast update * @param [in] clock_generator: Clock generator - * @param [in] id: Component ID + * @param [in] component_id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] @@ -54,7 +54,7 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int id, const double step_width, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -68,7 +68,7 @@ class RWModel : public Component, public ILoggable { * @param [in] fast_prescaler: Frequency scale factor for fast update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] id: Component ID + * @param [in] component_id: Component ID * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] @@ -91,7 +91,7 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int id, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -184,7 +184,7 @@ class RWModel : public Component, public ILoggable { protected: // Fixed Parameters - const int component_id_; //!< Actuator ID + const int component_id_; //!< Actuator ID const double inertia_; //!< Inertia of RW rotor [kgm2] const double max_torque_; //!< Maximum output torque [Nm] const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 04198a447..169d2ce82 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -15,12 +15,12 @@ using namespace std; using namespace libra; -STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, - const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, - const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, - const Dynamics* dynamics, const LocalEnvironment* local_env) +STT::STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, + const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, + const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, + const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), @@ -38,12 +38,12 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int id, con local_env_(local_env) { Initialize(); } -STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, +STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) : Component(prescaler, clock_generator, power_port), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), rot_(global_randomization.MakeSeed()), n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), @@ -101,8 +101,8 @@ Quaternion STT::measure(const LocalCelestialInformation* local_celes_info, const } void STT::update(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { - Quaternion q_i2b = attinfo->GetQuaternion_i2b(); // Read true value - Quaternion q_stt_temp = q_i2b * quaternion_b2c_; // Convert to component frame + Quaternion quaternion_i2b = attinfo->GetQuaternion_i2b(); // Read true value + Quaternion q_stt_temp = quaternion_i2b * quaternion_b2c_; // Convert to component frame // Add noise on sight direction Quaternion q_sight(sight_, n_sight_); // Random noise on orthogonal direction of sight. Range [0:2pi] diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 26a5f0ed7..2a598f045 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -29,7 +29,7 @@ class STT : public Component, public ILoggable { * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] @@ -43,7 +43,7 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, + STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); @@ -53,7 +53,7 @@ class STT : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] @@ -67,7 +67,7 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_env: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, + STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env); @@ -104,7 +104,7 @@ class STT : public Component, public ILoggable { protected: // STT general parameters - const int component_id_; //!< Sensor ID + const int component_id_; //!< Sensor ID libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame libra::Quaternion q_stt_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion libra::Vector<3> sight_; //!< Sight direction vector at component frame diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 4a9d57541..83d2aec91 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -13,12 +13,12 @@ using libra::NormalRand; using namespace std; -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), @@ -27,12 +27,12 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const Initialize(nr_stddev_c, nr_bias_stddev_c); } -SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, +SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator, power_port), - component_id_(id), + component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 7d43385c9..583a83e8f 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -26,7 +26,7 @@ class SunSensor : public Component, public ILoggable { * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] @@ -35,7 +35,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_generator, const int id, const libra::Quaternion& quaternion_b2c, + SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); @@ -45,7 +45,7 @@ class SunSensor : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] id: Sensor ID + * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] @@ -54,8 +54,8 @@ class SunSensor : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, + SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index b01fd1816..1f50ba0fe 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -8,9 +8,9 @@ #include #include -Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, - const Vector<4> tx_params, const Vector<4> rx_params) - : component_id_(id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { +Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, + const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) + : component_id_(component_id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { quaternion_b2c_ = quaternion_b2c; // Parameters @@ -41,10 +41,10 @@ Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bo } } -Antenna::Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, - const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, - const AntennaParameters rx_params) - : component_id_(id), +Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, + const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, + const double rx_system_noise_temperature_K, const AntennaParameters rx_params) + : component_id_(component_id), quaternion_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index aeea9ea2e..98821dd0e 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -46,7 +46,7 @@ class Antenna { * @fn Antenna * @brief Constructor * @note TODO: This constructor will be removed. - * @param [in] id: Antenna ID + * @param [in] component_id: Antenna ID * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not @@ -54,13 +54,13 @@ class Antenna { * @param [in] tx_params: output, gain, loss_feeder, loss_pointing for TX * @param [in] rx_params: gain, loss_feeder, loss_pointing, system_temperature for RX */ - Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, + Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const Vector<4> tx_params, const Vector<4> rx_params); /** * @fn Antenna * @brief Constructor - * @param [in] id: Antenna ID + * @param [in] component_id: Antenna ID * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not @@ -70,7 +70,7 @@ class Antenna { * @param [in] rx_system_noise_temperature_K: Receive system noise temperature [K] * @param [in] rx_params: RX antenna parameters */ - Antenna(const int id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, + Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, const AntennaParameters rx_params); /** @@ -121,7 +121,7 @@ class Antenna { protected: // General info - int component_id_; //!< Antenna ID + int component_id_; //!< Antenna ID Quaternion quaternion_b2c_; //!< Coordinate transform from body to component bool is_transmitter_; //!< Antenna for transmitter or not bool is_receiver_; //!< Antenna for receiver or not diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 7388a8078..945cc5e71 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -104,13 +104,13 @@ void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target } void Telescope::ObserveStars() { - Quaternion q_i2b = attitude_->GetQuaternion_i2b(); + Quaternion quaternion_i2b = attitude_->GetQuaternion_i2b(); star_in_sight.clear(); // Clear first int count = 0; // Counter for while loop while (star_in_sight.size() < num_of_logged_stars_) { - Vector<3> target_b = hipp_->GetStarDirection_b(count, q_i2b); + Vector<3> target_b = hipp_->GetStarDirection_b(count, quaternion_i2b); Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 8204f7730..65b00826a 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -8,11 +8,11 @@ #include #include -SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, +SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), @@ -26,11 +26,11 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int numbe power_generation_ = 0.0; } -SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, +SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), @@ -43,11 +43,11 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int id, int numbe power_generation_ = 0.0; } -SAP::SAP(ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, - double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, +SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(10, clock_generator), - component_id_(id), + component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_(cell_area), diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index e39b5fc90..9090e8846 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -20,7 +20,7 @@ class SAP : public Component, public ILoggable { * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: SAP ID + * @param [in] component_id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells * @param [in] cell_area: Area of a solar cell [m2] @@ -31,7 +31,7 @@ class SAP : public Component, public ILoggable { * @param [in] local_celes_info: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, + SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info, double compo_step_time); /** @@ -39,7 +39,7 @@ class SAP : public Component, public ILoggable { * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: SAP ID + * @param [in] component_id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells * @param [in] cell_area: Area of a solar cell [m2] @@ -49,7 +49,7 @@ class SAP : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] compo_step_time: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, + SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, double compo_step_time); /** @@ -57,7 +57,7 @@ class SAP : public Component, public ILoggable { * @brief Constructor without prescaler * @note prescaler is set as 10, compo_step_sec is set as * @param [in] clock_generator: Clock generator - * @param [in] id: SAP ID + * @param [in] component_id: SAP ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells * @param [in] cell_area: Area of a solar cell [m2] @@ -67,8 +67,8 @@ class SAP : public Component, public ILoggable { * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ - SAP(ClockGenerator* clock_generator, int id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, - double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, + SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** * @fn SAP @@ -105,7 +105,7 @@ class SAP : public Component, public ILoggable { std::string GetLogValue() const override; private: - const int component_id_; //!< SAP ID TODO: Use string? + const int component_id_; //!< SAP ID TODO: Use string? const int number_of_series_; //!< Number of series connected solar cells const int number_of_parallel_; //!< Number of parallel connected solar cells const double cell_area_; //!< Solar cell area [m^2] diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 884d629eb..49ca9fe37 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -9,11 +9,11 @@ #include // Constructor -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int id, const Vector<3> thruster_pos_b, +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), - component_id_(id), + component_id_(component_id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), thrust_magnitude_max_(max_mag), @@ -23,11 +23,11 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera Initialize(mag_err, dir_err); } -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), - component_id_(id), + component_id_(component_id), thruster_pos_b_(thruster_pos_b), thrust_dir_b_(thrust_dir_b), thrust_magnitude_max_(max_mag), diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 81556b127..5468af7e3 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -26,7 +26,7 @@ class SimpleThruster : public Component, public ILoggable { * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] id: Thruster ID + * @param [in] component_id: Thruster ID * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame * @param [in] max_mag: Maximum thrust magnitude [N] @@ -35,15 +35,16 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, - const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics); + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, + const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, + const Dynamics* dynamics); /** * @fn SimpleThruster * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] id: Thruster ID + * @param [in] component_id: Thruster ID * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame * @param [in] max_mag: Maximum thrust magnitude [N] @@ -52,7 +53,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int id, const Vector<3> thruster_pos_b, + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, const Dynamics* dynamics); /** @@ -106,7 +107,7 @@ class SimpleThruster : public Component, public ILoggable { protected: // parameters - const int component_id_; //!< Thruster ID + const int component_id_; //!< Thruster ID Vector<3> thruster_pos_b_{0.0}; //!< Thruster position @ body frame [m] Vector<3> thrust_dir_b_{0.0}; //!< Thrust direction @ body frame double duty_ = 0.0; //!< PWM Duty [0.0 : 1.0] diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 9475fff6f..05650aa13 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -50,8 +50,8 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // GNSS-R ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - gnss_ = new GNSSReceiver( - InitGNSSReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); + gnss_ = new GnssReceiver( + InitGnssReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); // MagTorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 8aefc19f9..60f485f78 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -36,7 +36,7 @@ class Gyro; class MagSensor; class STT; class SunSensor; -class GNSSReceiver; +class GnssReceiver; class MagTorquer; class RWModel; class SimpleThruster; @@ -91,7 +91,7 @@ class SampleComponents : public InstalledComponents { MagSensor* mag_sensor_; //!< Magnetmeter STT* stt_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor - GNSSReceiver* gnss_; //!< GNSS receiver + GnssReceiver* gnss_; //!< GNSS receiver MagTorquer* mag_torquer_; //!< Magnetorquer RWModel* rw_; //!< Reaction Wheel SimpleThruster* thruster_; //!< Thruster From 9732592a2df383fdcc59cc2b2afeba07b2ca2afd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:45:10 +0100 Subject: [PATCH 0781/1086] Fix function argument name --- src/components/real/aocs/gnss_receiver.cpp | 19 ++++++++++--------- src/components/real/aocs/gnss_receiver.hpp | 8 ++++---- .../real/aocs/initialize_gnss_receiver.cpp | 8 ++++---- 3 files changed, 18 insertions(+), 17 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index dfde402e2..aada5f787 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -9,13 +9,13 @@ #include #include -GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, const int ch_max, - const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, - const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, - const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) +GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, + const int max_channel, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, + const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, + const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) : Component(prescaler, clock_generator), component_id_(component_id), - max_channel_(ch_max), + max_channel_(max_channel), antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), @@ -28,12 +28,13 @@ GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, gnss_satellites_(gnss_satellites), simulation_time_(simulation_time) {} GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const std::string gnss_id, const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, - const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, - const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) + const std::string gnss_id, const int max_channel, const AntennaModel antenna_model, + const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, + const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, + const SimulationTime* simulation_time) : Component(prescaler, clock_generator, power_port), component_id_(component_id), - max_channel_(ch_max), + max_channel_(max_channel), antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index c5fc7d58e..e03db7dc5 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -48,7 +48,7 @@ class GnssReceiver : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] component_id: Component ID * @param [in] gnss_id: GNSS satellite number defined by GNSS system - * @param [in] ch_max: Maximum number of channels + * @param [in] max_channel: Maximum number of channels * @param [in] antenna_model: Antenna model * @param [in] antenna_position_b_m: GNSS antenna position at the body-fixed frame [m] * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) @@ -58,7 +58,7 @@ class GnssReceiver : public Component, public ILoggable { * @param [in] gnss_satellites: GNSS Satellites information * @param [in] simulation_time: Simulation time information */ - GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, const int ch_max, + GnssReceiver(const int prescaler, ClockGenerator* clock_generator, const int component_id, const std::string gnss_id, const int max_channel, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); @@ -69,7 +69,7 @@ class GnssReceiver : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] gnss_id: GNSS satellite number defined by GNSS system - * @param [in] ch_max: Maximum number of channels + * @param [in] max_channel: Maximum number of channels * @param [in] antenna_model: Antenna model * @param [in] antenna_position_b_m: GNSS antenna position at the body-fixed frame [m] * @param [in] quaternion_b2c: Quaternion from body frame to component frame (antenna frame) @@ -80,7 +80,7 @@ class GnssReceiver : public Component, public ILoggable { * @param [in] simulation_time: Simulation time information */ GnssReceiver(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, std::string gnss_id, - const int ch_max, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, + const int max_channel, const AntennaModel antenna_model, const libra::Vector<3> antenna_position_b_m, const libra::Quaternion quaternion_b2c, const double half_width_rad, const libra::Vector<3> noise_standard_deviation_m, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index 7f88bcac9..046b2c064 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -15,7 +15,7 @@ typedef struct _gnssrecever_param { Quaternion quaternion_b2c; double half_width_rad; std::string gnss_id; - int ch_max; + int max_channel; Vector<3> noise_standard_deviation_m; } GnssReceiverParam; @@ -43,7 +43,7 @@ GnssReceiverParam ReadGnssReceiverIni(const std::string fname, const GnssSatelli gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnssreceiver_param.quaternion_b2c); gnssreceiver_param.half_width_rad = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); gnssreceiver_param.gnss_id = gnssr_conf.ReadString(GSection, "gnss_id"); - gnssreceiver_param.ch_max = gnssr_conf.ReadInt(GSection, "maximum_channel"); + gnssreceiver_param.max_channel = gnssr_conf.ReadInt(GSection, "maximum_channel"); gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnssreceiver_param.noise_standard_deviation_m); return gnssreceiver_param; @@ -53,7 +53,7 @@ GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { GnssReceiverParam gr_param = ReadGnssReceiverIni(fname, gnss_satellites, component_id); - GnssReceiver gnss_r(gr_param.prescaler, clock_generator, component_id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, + GnssReceiver gnss_r(gr_param.prescaler, clock_generator, component_id, gr_param.gnss_id, gr_param.max_channel, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, gnss_satellites, simulation_time); return gnss_r; @@ -66,7 +66,7 @@ GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_ // PowerPort power_port->InitializeWithInitializeFile(fname); - GnssReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, component_id, gr_param.gnss_id, gr_param.ch_max, gr_param.antenna_model, + GnssReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, component_id, gr_param.gnss_id, gr_param.max_channel, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, gnss_satellites, simulation_time); return gnss_r; From 23d2892050e73157b94f042f72bc8ae7b6d157a0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:50:45 +0100 Subject: [PATCH 0782/1086] Fix private variables name --- src/components/real/aocs/gnss_receiver.cpp | 44 +++++++++++----------- src/components/real/aocs/gnss_receiver.hpp | 12 +++--- 2 files changed, 28 insertions(+), 28 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index aada5f787..6c29c1000 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -18,9 +18,9 @@ GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, max_channel_(max_channel), antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), - nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), - nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), - nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), + random_noise_i_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), + random_noise_i_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), + random_noise_i_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), half_width_rad_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), @@ -37,9 +37,9 @@ GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, max_channel_(max_channel), antenna_position_b_m_(antenna_position_b_m), quaternion_b2c_(quaternion_b2c), - nrs_eci_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), - nrs_eci_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), - nrs_eci_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), + random_noise_i_x_(0.0, noise_standard_deviation_m[0], global_randomization.MakeSeed()), + random_noise_i_y_(0.0, noise_standard_deviation_m[1], global_randomization.MakeSeed()), + random_noise_i_z_(0.0, noise_standard_deviation_m[2], global_randomization.MakeSeed()), half_width_rad_(half_width_rad), gnss_id_(gnss_id), antenna_model_(antenna_model), @@ -47,8 +47,8 @@ GnssReceiver::GnssReceiver(const int prescaler, ClockGenerator* clock_generator, gnss_satellites_(gnss_satellites), simulation_time_(simulation_time) {} -void GnssReceiver::MainRoutine(int count) { - UNUSED(count); +void GnssReceiver::MainRoutine(const int time_count) { + UNUSED(time_count); libra::Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); Quaternion quaternion_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); @@ -96,7 +96,7 @@ void GnssReceiver::CheckAntennaSimple(const libra::Vector<3> pos_true_eci_, libr void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra::Quaternion quaternion_i2b) { // Cone model - libra::Vector<3> gnss_sat_pos_i, ant_pos_i, ant2gnss_i, ant2gnss_i_n, sat2ant_i; + libra::Vector<3> gnss_sat_pos_i, ant_pos_i, antenna_to_satellite_i_m, ant2gnss_i_n, sat2ant_i; gnss_information_list_.clear(); // antenna normal vector at inertial frame @@ -120,9 +120,9 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: // compute direction from sat to gnss in body-fixed frame gnss_sat_pos_i = gnss_satellites_->GetSatellitePositionEci(i); - ant2gnss_i = gnss_sat_pos_i - ant_pos_i; - double normalizer = 1 / CalcNorm(ant2gnss_i); - ant2gnss_i_n = normalizer * ant2gnss_i; + antenna_to_satellite_i_m = gnss_sat_pos_i - ant_pos_i; + double normalizer = 1 / CalcNorm(antenna_to_satellite_i_m); + ant2gnss_i_n = normalizer * antenna_to_satellite_i_m; // check gnss sats are visible from antenna double Re = environment::earth_equatorial_radius_m; @@ -131,7 +131,7 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: if (inner1 > 0) is_visible_ant2gnss = 1; else { - Vector<3> tmp = ant_pos_i + InnerProduct(-ant_pos_i, ant2gnss_i_n) * ant2gnss_i; + Vector<3> tmp = ant_pos_i + InnerProduct(-ant_pos_i, ant2gnss_i_n) * antenna_to_satellite_i_m; if (CalcNorm(tmp) < Re) // There is earth between antenna and gnss is_visible_ant2gnss = 0; @@ -144,7 +144,7 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: if (inner2 > cos(half_width_rad_ * libra::deg_to_rad) && is_visible_ant2gnss) { // is visible visible_satellite_number_++; - SetGnssInfo(ant2gnss_i, quaternion_i2b, id_tmp); + SetGnssInfo(antenna_to_satellite_i_m, quaternion_i2b, id_tmp); } } @@ -154,10 +154,10 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: is_gnss_visible_ = 0; } -void GnssReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion quaternion_i2b, std::string gnss_id) { +void GnssReceiver::SetGnssInfo(libra::Vector<3> antenna_to_satellite_i_m, libra::Quaternion quaternion_i2b, std::string gnss_id) { libra::Vector<3> ant2gnss_b, ant2gnss_c; - ant2gnss_b = quaternion_i2b.FrameConversion(ant2gnss_i); + ant2gnss_b = quaternion_i2b.FrameConversion(antenna_to_satellite_i_m); ant2gnss_c = quaternion_b2c_.FrameConversion(ant2gnss_b); double dist = CalcNorm(ant2gnss_c); @@ -170,14 +170,14 @@ void GnssReceiver::SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion qu void GnssReceiver::AddNoise(libra::Vector<3> position_true_i_m, libra::Vector<3> position_true_ecef_m) { // Simplest noise model - position_eci_m_[0] = position_true_i_m[0] + nrs_eci_x_; - position_eci_m_[1] = position_true_i_m[1] + nrs_eci_y_; - position_eci_m_[2] = position_true_i_m[2] + nrs_eci_z_; + position_eci_m_[0] = position_true_i_m[0] + random_noise_i_x_; + position_eci_m_[1] = position_true_i_m[1] + random_noise_i_y_; + position_eci_m_[2] = position_true_i_m[2] + random_noise_i_z_; // FIXME: noise in ECI frame is added to ECEF frame value - position_ecef_m_[0] = position_true_ecef_m[0] + nrs_eci_x_; - position_ecef_m_[1] = position_true_ecef_m[1] + nrs_eci_y_; - position_ecef_m_[2] = position_true_ecef_m[2] + nrs_eci_z_; + position_ecef_m_[0] = position_true_ecef_m[0] + random_noise_i_x_; + position_ecef_m_[1] = position_true_ecef_m[1] + random_noise_i_y_; + position_ecef_m_[2] = position_true_ecef_m[2] + random_noise_i_z_; } void GnssReceiver::ConvertJulianDayToGPSTime(const double julian_day) { diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index e03db7dc5..8306f8442 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -89,15 +89,15 @@ class GnssReceiver : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count); + void MainRoutine(const int time_count); // Getter /** * @fn GetGnssInfo * @brief Return GNSS satellite information - * @param [in] ch: Channel number + * @param [in] channel: Channel number */ - inline const GnssInfo GetGnssInfo(int ch) const { return gnss_information_list_[ch]; }; + inline const GnssInfo GetGnssInfo(int channel) const { return gnss_information_list_[channel]; }; /** * @fn GetPositionECI * @brief Return Observed position in the ECI frame [m] @@ -143,7 +143,7 @@ class GnssReceiver : public Component, public ILoggable { libra::Vector<3> antenna_position_b_m_; //!< GNSS antenna position at the body-fixed frame [m] libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (antenna frame) - libra::NormalRand nrs_eci_x_, nrs_eci_y_, nrs_eci_z_; //!< Random noise for each axis + libra::NormalRand random_noise_i_x_, random_noise_i_y_, random_noise_i_z_; //!< Random noise for each axis double half_width_rad_ = 0.0; //!< Half width of the antenna cone model [rad] std::string gnss_id_; //!< GNSS satellite number defined by GNSS system @@ -195,11 +195,11 @@ class GnssReceiver : public Component, public ILoggable { /** * @fn SetGnssInfo * @brief Calculate and set the GnssInfo values of target GNSS satellite - * @param [in] ant2gnss_i: Position vector from the antenna to the GNSS satellites in the ECI frame + * @param [in] antenna_to_satellite_i_m: Position vector from the antenna to the GNSS satellites in the ECI frame * @param [in] quaternion_i2b: True attitude of the spacecraft expressed by quaternion from the inertial frame to the body-fixed frame * @param [in] gnss_id: ID of target GNSS satellite */ - void SetGnssInfo(libra::Vector<3> ant2gnss_i, libra::Quaternion quaternion_i2b, std::string gnss_id); + void SetGnssInfo(libra::Vector<3> antenna_to_satellite_i_m, libra::Quaternion quaternion_i2b, std::string gnss_id); /** * @fn AddNoise * @brief Substitutional method for "Measure" in other sensor models inherited Sensor class From 0702f36419c3ffb7606b03dff1e3fbb87951f9c4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:52:59 +0100 Subject: [PATCH 0783/1086] Fix public function name --- src/components/real/aocs/gnss_receiver.hpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 8306f8442..a61bae928 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -99,30 +99,30 @@ class GnssReceiver : public Component, public ILoggable { */ inline const GnssInfo GetGnssInfo(int channel) const { return gnss_information_list_[channel]; }; /** - * @fn GetPositionECI + * @fn GetMeasuredPosition_i_m * @brief Return Observed position in the ECI frame [m] */ - inline const libra::Vector<3> GetPositionECI(void) const { return position_eci_m_; } + inline const libra::Vector<3> GetMeasuredPosition_i_m(void) const { return position_eci_m_; } /** - * @fn GetPositionECEF + * @fn GetMeasuredPosition_ecef_m * @brief Return Observed position in the ECEF frame [m] */ - inline const libra::Vector<3> GetPositionECEF(void) const { return position_ecef_m_; } + inline const libra::Vector<3> GetMeasuredPosition_ecef_m(void) const { return position_ecef_m_; } /** - * @fn GetPositionLLH + * @fn GetMeasuredGeodeticPosition * @brief Return Observed position in the LLH frame [m] */ - inline const libra::Vector<3> GetPositionLLH(void) const { return position_llh_; } + inline const libra::Vector<3> GetMeasuredGeodeticPosition(void) const { return position_llh_; } /** - * @fn GetVelocityECI + * @fn GetMeasuredVelocity_i_m_s * @brief Return Observed velocity in the ECI frame [m/s] */ - inline const libra::Vector<3> GetVelocityECI(void) const { return velocity_eci_m_s_; } + inline const libra::Vector<3> GetMeasuredVelocity_i_m_s(void) const { return velocity_eci_m_s_; } /** - * @fn GetVelocityECEF + * @fn GetMeasuredVelocity_ecef_m_s * @brief Return Observed velocity in the ECEF frame [m/s] */ - inline const libra::Vector<3> GetVelocityECEF(void) const { return velocity_ecef_m_s_; } + inline const libra::Vector<3> GetMeasuredVelocity_ecef_m_s(void) const { return velocity_ecef_m_s_; } // Override ILoggable /** From a62f4a976c4b8f9eb828100f3f54f3f0de30c48f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 27 Feb 2023 13:58:34 +0100 Subject: [PATCH 0784/1086] Fix public function to use GeodeticPosition --- src/components/real/aocs/gnss_receiver.hpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index a61bae928..8018fb2a5 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -9,6 +9,7 @@ #include #include #include +#include #include #include #include @@ -99,10 +100,10 @@ class GnssReceiver : public Component, public ILoggable { */ inline const GnssInfo GetGnssInfo(int channel) const { return gnss_information_list_[channel]; }; /** - * @fn GetMeasuredPosition_i_m + * @fn GetMeasuredPosition_eci_m * @brief Return Observed position in the ECI frame [m] */ - inline const libra::Vector<3> GetMeasuredPosition_i_m(void) const { return position_eci_m_; } + inline const libra::Vector<3> GetMeasuredPosition_eci_m(void) const { return position_eci_m_; } /** * @fn GetMeasuredPosition_ecef_m * @brief Return Observed position in the ECEF frame [m] @@ -112,12 +113,15 @@ class GnssReceiver : public Component, public ILoggable { * @fn GetMeasuredGeodeticPosition * @brief Return Observed position in the LLH frame [m] */ - inline const libra::Vector<3> GetMeasuredGeodeticPosition(void) const { return position_llh_; } + inline const GeodeticPosition GetMeasuredGeodeticPosition(void) const { + GeodeticPosition geodetic_position(position_llh_[0], position_llh_[1], position_llh_[2]); + return geodetic_position; + } /** - * @fn GetMeasuredVelocity_i_m_s + * @fn GetMeasuredVelocity_eci_m_s * @brief Return Observed velocity in the ECI frame [m/s] */ - inline const libra::Vector<3> GetMeasuredVelocity_i_m_s(void) const { return velocity_eci_m_s_; } + inline const libra::Vector<3> GetMeasuredVelocity_eci_m_s(void) const { return velocity_eci_m_s_; } /** * @fn GetMeasuredVelocity_ecef_m_s * @brief Return Observed velocity in the ECEF frame [m/s] From 7e1261be7638301f88c915ee986da28d2282a8ef Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:03:48 +0100 Subject: [PATCH 0785/1086] Rename Gyro to GyroSensor --- src/components/real/aocs/gyro_sensor.cpp | 20 ++++++------ src/components/real/aocs/gyro_sensor.hpp | 31 ++++++++++--------- .../real/aocs/initialize_gyro_sensor.cpp | 14 ++++----- .../real/aocs/initialize_gyro_sensor.hpp | 6 ++-- .../sample_spacecraft/sample_components.cpp | 6 ++-- .../sample_spacecraft/sample_components.hpp | 4 +-- 6 files changed, 41 insertions(+), 40 deletions(-) diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index ec8f7f626..679c6dfe8 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,11 +5,11 @@ #include "gyro_sensor.hpp" -Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, +GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} -Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, +GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), @@ -17,28 +17,28 @@ Gyro::Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* powe quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} -Gyro::~Gyro() {} +GyroSensor::~GyroSensor() {} -void Gyro::MainRoutine(int count) { +void GyroSensor::MainRoutine(int count) { UNUSED(count); - omega_c_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame - omega_c_ = Measure(omega_c_); // Add noises + angular_velocity_c_rad_s_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame + angular_velocity_c_rad_s_ = Measure(angular_velocity_c_rad_s_); // Add noises } -std::string Gyro::GetLogHeader() const { +std::string GyroSensor::GetLogHeader() const { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(sensor_id_)); std::string sensor_name = "gyro_sensor" + sensor_id + "_"; - str_tmp += WriteVector(sensor_name + "measured_angular_velocity", "c", "rad/s", kGyroDim); + str_tmp += WriteVector(sensor_name + "measured_angular_velocity", "c", "rad/s", kGyroDimension); return str_tmp; } -std::string Gyro::GetLogValue() const { +std::string GyroSensor::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(omega_c_); + str_tmp += WriteVector(angular_velocity_c_rad_s_); return str_tmp; } diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index e0538f15f..643cf1aa0 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -13,16 +13,16 @@ #include "../../base/component.hpp" #include "../../base/sensor.hpp" -const size_t kGyroDim = 3; //!< Dimension of gyro sensor +const size_t kGyroDimension = 3; //!< Dimension of gyro sensor /** - * @class Gyro + * @class GyroSensor * @brief Class to emulate gyro sensor */ -class Gyro : public Component, public Sensor, public ILoggable { +class GyroSensor : public Component, public Sensor, public ILoggable { public: /** - * @fn Gyro + * @fn GyroSensor * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -31,10 +31,10 @@ class Gyro : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, - const Dynamics* dynamics); + GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, + const Dynamics* dynamics); /** - * @fn Gyro + * @fn GyroSensor * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -44,13 +44,13 @@ class Gyro : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - Gyro(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); + GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); /** - * @fn ~Gyro + * @fn ~GyroSensor * @brief Destructor */ - ~Gyro(); + ~GyroSensor(); // Override functions for Component /** @@ -72,14 +72,15 @@ class Gyro : public Component, public Sensor, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetOmegaC + * @fn GetMeasuredAngularVelocity_c_rad_s * @brief Return observed angular velocity of the component frame with respect to the inertial frame */ - inline const libra::Vector& GetOmegaC(void) const { return omega_c_; } + inline const libra::Vector& GetMeasuredAngularVelocity_c_rad_s(void) const { return angular_velocity_c_rad_s_; } protected: - libra::Vector omega_c_{0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] - int sensor_id_ = 0; //!< Sensor ID + libra::Vector angular_velocity_c_rad_s_{ + 0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] + int sensor_id_ = 0; //!< Sensor ID libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const Dynamics* dynamics_; //!< Dynamics information diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index a492c9248..06e793a79 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -8,7 +8,7 @@ #include "../../base/initialize_sensor.hpp" -Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { IniAccess gyro_conf(fname); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -20,15 +20,15 @@ Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); - Gyro gyro(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, dynamics); + GyroSensor gyro(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } -Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const Dynamics* dynamics) { +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, + const Dynamics* dynamics) { IniAccess gyro_conf(fname); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -40,11 +40,11 @@ Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); // PowerPort power_port->InitializeWithInitializeFile(fname); - Gyro gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, dynamics); + GyroSensor gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } diff --git a/src/components/real/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp index 56cff2a6b..f22c34e9f 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -17,7 +17,7 @@ * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information */ -Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); /** * @fn InitGyro * @brief Initialize functions for gyro sensor with power port @@ -28,7 +28,7 @@ Gyro InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string * @param [in] fname: Path to the initialize file * @param [in] dynamics: Dynamics information */ -Gyro InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const Dynamics* dynamics); +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, + const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 05650aa13..6292cc225 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -17,17 +17,17 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // PCU power port connection pcu_ = new PCU(clock_gen); pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here - pcu_->ConnectPort(1, 1.0); // Gyro: assumed power consumption is defined inside the InitGyro + pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyro pcu_->ConnectPort(2, 1.0); // for other all components // Components obc_ = new OBC(1, clock_gen, pcu_->GetPowerPort(0)); hils_port_manager_ = new HilsPortManager(); - // Gyro + // GyroSensor std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - gyro_ = new Gyro(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); + gyro_ = new GyroSensor(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // MagSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 60f485f78..737a50d0b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -32,7 +32,7 @@ class OBC; class PCU; -class Gyro; +class GyroSensor; class MagSensor; class STT; class SunSensor; @@ -87,7 +87,7 @@ class SampleComponents : public InstalledComponents { HilsPortManager* hils_port_manager_; //!< Port manager for HILS test // AOCS - Gyro* gyro_; //!< Gyro sensor + GyroSensor* gyro_; //!< GyroSensor sensor MagSensor* mag_sensor_; //!< Magnetmeter STT* stt_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor From 7bd89e51c22298270294100fbde5a20e2cc3465b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:04:42 +0100 Subject: [PATCH 0786/1086] Fix function arguments --- src/components/real/aocs/gyro_sensor.cpp | 10 +++++----- src/components/real/aocs/gyro_sensor.hpp | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index 679c6dfe8..6dd7f921e 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,12 +5,12 @@ #include "gyro_sensor.hpp" -GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, - const Dynamics* dynamics) +GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, + const Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, - const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), @@ -19,8 +19,8 @@ GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Pow GyroSensor::~GyroSensor() {} -void GyroSensor::MainRoutine(int count) { - UNUSED(count); +void GyroSensor::MainRoutine(const int time_count) { + UNUSED(time_count); angular_velocity_c_rad_s_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame angular_velocity_c_rad_s_ = Measure(angular_velocity_c_rad_s_); // Add noises diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index 643cf1aa0..637e52f4c 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -57,7 +57,7 @@ class GyroSensor : public Component, public Sensor, public ILogg * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** From 3161a41e4dd92f3f551e0031fb92f01880e80d92 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:07:07 +0100 Subject: [PATCH 0787/1086] Add unsigned --- src/components/real/aocs/gyro_sensor.cpp | 4 ++-- src/components/real/aocs/gyro_sensor.hpp | 10 +++++----- src/components/real/aocs/magnetometer.cpp | 8 ++++++-- 3 files changed, 13 insertions(+), 9 deletions(-) diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index 6dd7f921e..26ccb0948 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -5,11 +5,11 @@ #include "gyro_sensor.hpp" -GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, +GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, const Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} -GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, +GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), diff --git a/src/components/real/aocs/gyro_sensor.hpp b/src/components/real/aocs/gyro_sensor.hpp index 637e52f4c..af8160c65 100644 --- a/src/components/real/aocs/gyro_sensor.hpp +++ b/src/components/real/aocs/gyro_sensor.hpp @@ -31,8 +31,8 @@ class GyroSensor : public Component, public Sensor, public ILogg * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, - const Dynamics* dynamics); + GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); /** * @fn GyroSensor * @brief Constructor with power port @@ -44,7 +44,7 @@ class GyroSensor : public Component, public Sensor, public ILogg * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] dynamics: Dynamics information */ - GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics); /** * @fn ~GyroSensor @@ -79,8 +79,8 @@ class GyroSensor : public Component, public Sensor, public ILogg protected: libra::Vector angular_velocity_c_rad_s_{ - 0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] - int sensor_id_ = 0; //!< Sensor ID + 0.0}; //!< Observed angular velocity of the component frame with respect to the inertial frame [rad/s] + unsigned int sensor_id_ = 0; //!< Sensor ID libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const Dynamics* dynamics_; //!< Dynamics information diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index fe9d63413..c85c43840 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -11,14 +11,18 @@ MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sen : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), magnet_(magnet) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, const GeomagneticField* magnet) - : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), magnet_(magnet) {} + : Component(prescaler, clock_generator, power_port), + Sensor(sensor_base), + sensor_id_(sensor_id), + quaternion_b2c_(quaternion_b2c), + magnet_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); mag_c_ = quaternion_b2c_.FrameConversion(magnet_->GetGeomagneticField_b_nT()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + mag_c_ = Measure(mag_c_); // Add noises } std::string MagSensor::GetLogHeader() const { From 5d5ad1f795eb211e979cdec2760bcc9e2e8c0ad9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:07:34 +0100 Subject: [PATCH 0788/1086] Add unsigned --- src/components/real/aocs/magnetometer.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 27c289a5a..43576a704 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -31,8 +31,8 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const libra::Quaternion& quaternion_b2c, - const GeomagneticField* magnet); + MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, + const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); /** * @fn MagSensor * @brief Constructor with power port @@ -44,7 +44,7 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] magnet: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, + MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); /** * @fn ~MagSensor @@ -79,7 +79,7 @@ class MagSensor : public Component, public Sensor, public ILoggable { protected: libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] - int sensor_id_ = 0; //!< Sensor ID + unsigned int sensor_id_ = 0; //!< Sensor ID libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const GeomagneticField* magnet_; //!< Geomagnetic environment From 6f4b4346be8ba25d9c4454c236a0aaa84fcbf2da Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:09:24 +0100 Subject: [PATCH 0789/1086] Fix private variables --- src/components/real/aocs/magnetometer.cpp | 20 ++++++++++++-------- src/components/real/aocs/magnetometer.hpp | 6 +++--- 2 files changed, 15 insertions(+), 11 deletions(-) diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index c85c43840..82316b4c2 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -6,23 +6,27 @@ #include -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const int sensor_id, const Quaternion& quaternion_b2c, - const GeomagneticField* magnet) - : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), magnet_(magnet) {} -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const int sensor_id, +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, + const Quaternion& quaternion_b2c, const GeomagneticField* magnet) + : Component(prescaler, clock_generator), + Sensor(sensor_base), + sensor_id_(sensor_id), + quaternion_b2c_(quaternion_b2c), + geomagnetic_field_(magnet) {} +MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, const Quaternion& quaternion_b2c, const GeomagneticField* magnet) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), - magnet_(magnet) {} + geomagnetic_field_(magnet) {} MagSensor::~MagSensor() {} void MagSensor::MainRoutine(int count) { UNUSED(count); - mag_c_ = quaternion_b2c_.FrameConversion(magnet_->GetGeomagneticField_b_nT()); // Convert frame - mag_c_ = Measure(mag_c_); // Add noises + magnetic_field_c_nT_ = quaternion_b2c_.FrameConversion(geomagnetic_field_->GetGeomagneticField_b_nT()); // Convert frame + magnetic_field_c_nT_ = Measure(magnetic_field_c_nT_); // Add noises } std::string MagSensor::GetLogHeader() const { @@ -37,7 +41,7 @@ std::string MagSensor::GetLogHeader() const { std::string MagSensor::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(mag_c_); + str_tmp += WriteVector(magnetic_field_c_nT_); return str_tmp; } diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 43576a704..19d875f10 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -75,14 +75,14 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @fn GetMagC * @brief Return observed magnetic field on the component frame */ - inline const libra::Vector& GetMagC(void) const { return mag_c_; } + inline const libra::Vector& GetMagC(void) const { return magnetic_field_c_nT_; } protected: - libra::Vector mag_c_{0.0}; // observed magnetic field on the component frame [nT] + libra::Vector magnetic_field_c_nT_{0.0}; //!< Observed magnetic field on the component frame [nT] unsigned int sensor_id_ = 0; //!< Sensor ID libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame - const GeomagneticField* magnet_; //!< Geomagnetic environment + const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment }; #endif // S2E_COMPONENTS_REAL_AOCS_MAGNETOMETER_HPP_ From 9eb61ca3b6c683384e4dd1b297a54077f5018319 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:11:15 +0100 Subject: [PATCH 0790/1086] Fix function argument names --- src/components/real/aocs/initialize_magnetometer.cpp | 8 ++++---- src/components/real/aocs/initialize_magnetometer.hpp | 4 ++-- src/components/real/aocs/magnetometer.cpp | 12 ++++++------ src/components/real/aocs/magnetometer.hpp | 10 +++++----- src/components/real/aocs/magnetorquer.hpp | 4 ++-- 5 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index 7e3864a33..d60672680 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -8,7 +8,7 @@ #include "library/initialize/initialize_file_access.hpp" MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* magnet) { + const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -23,12 +23,12 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const st // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); - MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* magnet) { + const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -46,6 +46,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, // PowerPort power_port->InitializeWithInitializeFile(fname); - MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, magnet); + MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 03648b087..759d3305a 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -17,7 +17,7 @@ * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* magnet); +MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* geomagnetic_field); /** * @fn InitMagSensor * @brief Initialize functions for magnetometer with power port @@ -29,6 +29,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] mgnet: Geomegnetic environment */ MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* magnet); + const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 82316b4c2..3b905d60e 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -7,23 +7,23 @@ #include MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* magnet) + const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), - geomagnetic_field_(magnet) {} + geomagnetic_field_(geomagnetic_field) {} MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* magnet) + const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), - geomagnetic_field_(magnet) {} + geomagnetic_field_(geomagnetic_field) {} MagSensor::~MagSensor() {} -void MagSensor::MainRoutine(int count) { - UNUSED(count); +void MagSensor::MainRoutine(const int time_count) { + UNUSED(time_count); magnetic_field_c_nT_ = quaternion_b2c_.FrameConversion(geomagnetic_field_->GetGeomagneticField_b_nT()); // Convert frame magnetic_field_c_nT_ = Measure(magnetic_field_c_nT_); // Add noises diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 19d875f10..8890da06e 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -29,10 +29,10 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] magnet: Geomagnetic environment + * @param [in] geomagnetic_field: Geomagnetic environment */ MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); /** * @fn MagSensor * @brief Constructor with power port @@ -42,10 +42,10 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] sensor_base: Sensor base information * @param [in] sensor_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] magnet: Geomagnetic environment + * @param [in] geomagnetic_field: Geomagnetic environment */ MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, - const libra::Quaternion& quaternion_b2c, const GeomagneticField* magnet); + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); /** * @fn ~MagSensor * @brief Destructor @@ -57,7 +57,7 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 9f4d1378b..559186d55 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -39,7 +39,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] rw_stddev_c: Standard deviation of random walk noise in the component frame [Am2] * @param [in] rw_limit_c: Limit for random walk noise in the component frame [Am2] * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] - * @param [in] magnet: Geomagnetic environment + * @param [in] geomagnetic_field: Geomagnetic environment */ MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, @@ -61,7 +61,7 @@ class MagTorquer : public Component, public ILoggable { * @param [in] rw_stddev_c: Standard deviation of random walk noise in the component frame [Am2] * @param [in] rw_limit_c: Limit for random walk noise in the component frame [Am2] * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] - * @param [in] magnet: Geomagnetic environment + * @param [in] geomagnetic_field: Geomagnetic environment */ MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, From 4beac20b4a16b09ff0baf927c1724f1eff9acebe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:12:17 +0100 Subject: [PATCH 0791/1086] Rename MagSensor to Magnetometer --- .../real/aocs/initialize_magnetometer.cpp | 12 +++++----- .../real/aocs/initialize_magnetometer.hpp | 7 +++--- src/components/real/aocs/magnetometer.cpp | 16 ++++++------- src/components/real/aocs/magnetometer.hpp | 24 +++++++++---------- .../sample_spacecraft/sample_components.cpp | 6 ++--- .../sample_spacecraft/sample_components.hpp | 4 ++-- 6 files changed, 35 insertions(+), 34 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index d60672680..7887d9ad0 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,8 +7,8 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -23,12 +23,12 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const st // Sensor Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); - MagSensor magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); + Magnetometer magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } -MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(fname); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -46,6 +46,6 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, // PowerPort power_port->InitializeWithInitializeFile(fname); - MagSensor magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); + Magnetometer magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 759d3305a..e362fa6ee 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -17,7 +17,8 @@ * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const GeomagneticField* geomagnetic_field); +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field); /** * @fn InitMagSensor * @brief Initialize functions for magnetometer with power port @@ -28,7 +29,7 @@ MagSensor InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -MagSensor InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field); +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 3b905d60e..161a6d3f8 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -6,30 +6,30 @@ #include -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) +Magnetometer::Magnetometer(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, + const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), geomagnetic_field_(geomagnetic_field) {} -MagSensor::MagSensor(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) +Magnetometer::Magnetometer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, + const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), geomagnetic_field_(geomagnetic_field) {} -MagSensor::~MagSensor() {} +Magnetometer::~Magnetometer() {} -void MagSensor::MainRoutine(const int time_count) { +void Magnetometer::MainRoutine(const int time_count) { UNUSED(time_count); magnetic_field_c_nT_ = quaternion_b2c_.FrameConversion(geomagnetic_field_->GetGeomagneticField_b_nT()); // Convert frame magnetic_field_c_nT_ = Measure(magnetic_field_c_nT_); // Add noises } -std::string MagSensor::GetLogHeader() const { +std::string Magnetometer::GetLogHeader() const { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(sensor_id_)); std::string sensor_name = "magnetometer" + sensor_id + "_"; @@ -38,7 +38,7 @@ std::string MagSensor::GetLogHeader() const { return str_tmp; } -std::string MagSensor::GetLogValue() const { +std::string Magnetometer::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(magnetic_field_c_nT_); diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 8890da06e..61bff5615 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -16,13 +16,13 @@ const size_t kMagDim = 3; //!< Dimension of magnetometer /** - * @class MagSensor + * @class Magnetometer * @brief Class to emulate magnetometer */ -class MagSensor : public Component, public Sensor, public ILoggable { +class Magnetometer : public Component, public Sensor, public ILoggable { public: /** - * @fn MagSensor + * @fn Magnetometer * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -31,10 +31,10 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] geomagnetic_field: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); + Magnetometer(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); /** - * @fn MagSensor + * @fn Magnetometer * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -44,13 +44,13 @@ class MagSensor : public Component, public Sensor, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] geomagnetic_field: Geomagnetic environment */ - MagSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, - const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); + Magnetometer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field); /** - * @fn ~MagSensor + * @fn ~Magnetometer * @brief Destructor */ - ~MagSensor(); + ~Magnetometer(); // Override functions for Component /** @@ -72,10 +72,10 @@ class MagSensor : public Component, public Sensor, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetMagC + * @fn GetMeasuredMagneticField_c_nT * @brief Return observed magnetic field on the component frame */ - inline const libra::Vector& GetMagC(void) const { return magnetic_field_c_nT_; } + inline const libra::Vector& GetMeasuredMagneticField_c_nT(void) const { return magnetic_field_c_nT_; } protected: libra::Vector magnetic_field_c_nT_{0.0}; //!< Observed magnetic field on the component frame [nT] diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 6292cc225..2733501f3 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -29,11 +29,11 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur config_->main_logger_->CopyFileToLogDirectory(ini_path); gyro_ = new GyroSensor(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); - // MagSensor + // Magnetometer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_sensor_ = new MagSensor(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - &(local_env_->GetGeomagneticField()))); + mag_sensor_ = new Magnetometer(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + &(local_env_->GetGeomagneticField()))); // STT ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 737a50d0b..2b8ef858c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -33,7 +33,7 @@ class OBC; class PCU; class GyroSensor; -class MagSensor; +class Magnetometer; class STT; class SunSensor; class GnssReceiver; @@ -88,7 +88,7 @@ class SampleComponents : public InstalledComponents { // AOCS GyroSensor* gyro_; //!< GyroSensor sensor - MagSensor* mag_sensor_; //!< Magnetmeter + Magnetometer* mag_sensor_; //!< Magnetmeter STT* stt_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor GnssReceiver* gnss_; //!< GNSS receiver From 17205a08c6a9f34c353764732520fde85998e6c8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:13:13 +0100 Subject: [PATCH 0792/1086] Fix constant value --- src/components/real/aocs/initialize_magnetometer.cpp | 6 ++++-- src/components/real/aocs/magnetometer.cpp | 2 +- src/components/real/aocs/magnetometer.hpp | 12 ++++++------ 3 files changed, 11 insertions(+), 9 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index 7887d9ad0..0e490a41e 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -21,7 +21,8 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + Sensor sensor_base = + ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); Magnetometer magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; @@ -41,7 +42,8 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_por magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + Sensor sensor_base = + ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); // PowerPort power_port->InitializeWithInitializeFile(fname); diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 161a6d3f8..7b4c9cc66 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -33,7 +33,7 @@ std::string Magnetometer::GetLogHeader() const { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(sensor_id_)); std::string sensor_name = "magnetometer" + sensor_id + "_"; - str_tmp += WriteVector(sensor_name + "measured_magnetic_field", "c", "nT", kMagDim); + str_tmp += WriteVector(sensor_name + "measured_magnetic_field", "c", "nT", kMagnetometerDimension); return str_tmp; } diff --git a/src/components/real/aocs/magnetometer.hpp b/src/components/real/aocs/magnetometer.hpp index 61bff5615..31416a4a6 100644 --- a/src/components/real/aocs/magnetometer.hpp +++ b/src/components/real/aocs/magnetometer.hpp @@ -13,13 +13,13 @@ #include "../../base/component.hpp" #include "../../base/sensor.hpp" -const size_t kMagDim = 3; //!< Dimension of magnetometer +const size_t kMagnetometerDimension = 3; //!< Dimension of magnetometer /** * @class Magnetometer * @brief Class to emulate magnetometer */ -class Magnetometer : public Component, public Sensor, public ILoggable { +class Magnetometer : public Component, public Sensor, public ILoggable { public: /** * @fn Magnetometer @@ -75,12 +75,12 @@ class Magnetometer : public Component, public Sensor, public ILoggable * @fn GetMeasuredMagneticField_c_nT * @brief Return observed magnetic field on the component frame */ - inline const libra::Vector& GetMeasuredMagneticField_c_nT(void) const { return magnetic_field_c_nT_; } + inline const libra::Vector& GetMeasuredMagneticField_c_nT(void) const { return magnetic_field_c_nT_; } protected: - libra::Vector magnetic_field_c_nT_{0.0}; //!< Observed magnetic field on the component frame [nT] - unsigned int sensor_id_ = 0; //!< Sensor ID - libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Vector magnetic_field_c_nT_{0.0}; //!< Observed magnetic field on the component frame [nT] + unsigned int sensor_id_ = 0; //!< Sensor ID + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment }; From 5292a0375563d4ec6cf19d3516b8ec706c08dbb4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:19:57 +0100 Subject: [PATCH 0793/1086] Fix private variables name --- src/components/base/sensor.hpp | 2 +- .../base/sensor_template_functions.hpp | 4 +- src/components/real/aocs/magnetorquer.cpp | 58 +++++++++---------- src/components/real/aocs/magnetorquer.hpp | 34 +++++------ .../real/propulsion/simple_thruster.cpp | 6 +- .../real/propulsion/simple_thruster.hpp | 6 +- 6 files changed, 55 insertions(+), 55 deletions(-) diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index a63d17093..80a3dbe12 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -53,7 +53,7 @@ class Sensor { libra::Matrix scale_factor_; //!< Scale factor matrix libra::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame libra::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame - libra::Vector bias_c_; //!< Constant bias noise at the component frame + libra::Vector bias_c_Am2_; //!< Constant bias noise at the component frame libra::NormalRand normal_random_noise_c_[N]; //!< Normal random RandomWalk random_walk_noise_c_; //!< Random Walk diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index 5faf0bbbb..a10303059 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -15,7 +15,7 @@ Sensor::Sensor(const libra::Matrix& scale_factor, const libra::Vector libra::Vector Sensor::Measure(const libra::Vector true_value_c) { libra::Vector calc_value_c; calc_value_c = scale_factor_ * true_value_c; - calc_value_c += bias_c_; + calc_value_c += bias_c_Am2_; for (size_t i = 0; i < N; ++i) { calc_value_c[i] += random_walk_noise_c_[i]; calc_value_c[i] += normal_random_noise_c_[i]; diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 722a0cf37..09cc1fc38 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -17,15 +17,15 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), - q_c2b_(quaternion_b2c_.Conjugate()), + quaternion_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), - max_c_(max_c), - min_c_(min_c), - bias_c_(bias_c), - n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), - mag_env_(mag_env) { + max_magnetic_moment_c_Am2_(max_c), + min_magnetic_moment_c_Am2_(min_c), + bias_c_Am2_(bias_c), + random_walk_c_Am2_(rw_stepwidth, rw_stddev_c, rw_limit_c), + geomagnetic_field_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + random_noise_c_Am2_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } @@ -37,15 +37,15 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, Pow : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), - q_c2b_(quaternion_b2c_.Conjugate()), + quaternion_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), - max_c_(max_c), - min_c_(min_c), - bias_c_(bias_c), - n_rw_c_(rw_stepwidth, rw_stddev_c, rw_limit_c), - mag_env_(mag_env) { + max_magnetic_moment_c_Am2_(max_c), + min_magnetic_moment_c_Am2_(min_c), + bias_c_Am2_(bias_c), + random_walk_c_Am2_(rw_stepwidth, rw_stddev_c, rw_limit_c), + geomagnetic_field_(mag_env) { for (size_t i = 0; i < kMtqDim; i++) { - nrs_c_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + random_noise_c_Am2_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() } } @@ -55,31 +55,31 @@ void MagTorquer::MainRoutine(int count) { CalcOutputTorque(); } -void MagTorquer::PowerOffRoutine() { torque_b_ *= 0.0; } +void MagTorquer::PowerOffRoutine() { torque_b_Nm_ *= 0.0; } libra::Vector MagTorquer::CalcOutputTorque(void) { for (size_t i = 0; i < kMtqDim; ++i) { // Limit Check - if (mag_moment_c_[i] > max_c_[i]) { - mag_moment_c_[i] = max_c_[i]; - } else if (mag_moment_c_[i] < min_c_[i]) { - mag_moment_c_[i] = min_c_[i]; + if (output_magnetic_moment_c_Am2_[i] > max_magnetic_moment_c_Am2_[i]) { + output_magnetic_moment_c_Am2_[i] = max_magnetic_moment_c_Am2_[i]; + } else if (output_magnetic_moment_c_Am2_[i] < min_magnetic_moment_c_Am2_[i]) { + output_magnetic_moment_c_Am2_[i] = min_magnetic_moment_c_Am2_[i]; } // Add noise - mag_moment_c_[i] += bias_c_[i]; - mag_moment_c_[i] += n_rw_c_[i]; - mag_moment_c_[i] += nrs_c_[i]; + output_magnetic_moment_c_Am2_[i] += bias_c_Am2_[i]; + output_magnetic_moment_c_Am2_[i] += random_walk_c_Am2_[i]; + output_magnetic_moment_c_Am2_[i] += random_noise_c_Am2_[i]; } - mag_moment_c_ = scale_factor_ * mag_moment_c_; + output_magnetic_moment_c_Am2_ = scale_factor_ * output_magnetic_moment_c_Am2_; // Frame conversion component to body - mag_moment_b_ = q_c2b_.FrameConversion(mag_moment_c_); + output_magnetic_moment_b_Am2_ = quaternion_c2b_.FrameConversion(output_magnetic_moment_c_Am2_); // Calc magnetic torque [Nm] - torque_b_ = OuterProduct(mag_moment_b_, knT2T * mag_env_->GetGeomagneticField_b_nT()); + torque_b_Nm_ = OuterProduct(output_magnetic_moment_b_Am2_, kConvertNanoT2T * geomagnetic_field_->GetGeomagneticField_b_nT()); // Update Random Walk - ++n_rw_c_; + ++random_walk_c_Am2_; - return torque_b_; + return torque_b_Nm_; } std::string MagTorquer::GetLogHeader() const { @@ -95,8 +95,8 @@ std::string MagTorquer::GetLogHeader() const { std::string MagTorquer::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(mag_moment_b_); - str_tmp += WriteVector(torque_b_); + str_tmp += WriteVector(output_magnetic_moment_b_Am2_); + str_tmp += WriteVector(torque_b_Nm_); return str_tmp; } diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 559186d55..10e02b605 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -97,35 +97,35 @@ class MagTorquer : public Component, public ILoggable { * @fn GetMagMoment_b * @brief Return output magnetic moment in the body fixed frame [Am2] */ - inline const libra::Vector& GetMagMoment_b(void) const { return mag_moment_b_; }; + inline const libra::Vector& GetMagMoment_b(void) const { return output_magnetic_moment_b_Am2_; }; /** * @fn GetTorque_b * @brief Return output torque in the body fixed frame [Nm] */ - inline const libra::Vector& GetTorque_b(void) const { return torque_b_; }; + inline const libra::Vector& GetTorque_b(void) const { return torque_b_Nm_; }; /** * @fn SetMagMomentC * @brief Set output magnetic moment in the component frame [Am2] */ - inline void SetMagMomentC(const libra::Vector mag_moment_c) { mag_moment_c_ = mag_moment_c; }; + inline void SetMagMomentC(const libra::Vector mag_moment_c) { output_magnetic_moment_c_Am2_ = mag_moment_c; }; protected: - const int component_id_ = 0; //!< Actuator ID - const double knT2T = 1.0e-9; //!< Constant to convert nT to T - libra::Vector torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] - libra::Vector mag_moment_c_{0.0}; //!< Output output magnetic moment in the component frame [Am2] - libra::Vector mag_moment_b_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] - libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame - libra::Quaternion q_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame - libra::Matrix scale_factor_; //!< Scale factor matrix - libra::Vector max_c_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] - libra::Vector min_c_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] - libra::Vector bias_c_{0.0}; //!< Constant bias noise in the component frame [Am2] - RandomWalk n_rw_c_; //!< Random walk noise - libra::NormalRand nrs_c_[kMtqDim]; //!< Normal random noise + const int component_id_ = 0; //!< Actuator ID + const double kConvertNanoT2T = 1.0e-9; //!< Constant to convert nT to T + libra::Vector torque_b_Nm_{0.0}; //!< Output torque in the body fixed frame [Nm] + libra::Vector output_magnetic_moment_c_Am2_{0.0}; //!< Output output magnetic moment in the component frame [Am2] + libra::Vector output_magnetic_moment_b_Am2_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Quaternion quaternion_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame + libra::Matrix scale_factor_; //!< Scale factor matrix + libra::Vector max_magnetic_moment_c_Am2_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] + libra::Vector min_magnetic_moment_c_Am2_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] + libra::Vector bias_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_[kMtqDim]; //!< Normal random noise - const GeomagneticField* mag_env_; //!< Geomagnetic environment + const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment /** * @fn CalcOutputTorque diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 49ca9fe37..64cdcbee2 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -54,7 +54,7 @@ void SimpleThruster::MainRoutine(int count) { void SimpleThruster::PowerOffRoutine() { thrust_b_ *= 0.0; - torque_b_ *= 0.0; + torque_b_Nm_ *= 0.0; } void SimpleThruster::CalcThrust() { @@ -67,7 +67,7 @@ void SimpleThruster::CalcTorque(Vector<3> center) { Vector<3> vector_center2thruster = thruster_pos_b_ - center; Vector<3> torque = OuterProduct(vector_center2thruster, thrust_b_); - torque_b_ = torque; + torque_b_Nm_ = torque; } std::string SimpleThruster::GetLogHeader() const { @@ -84,7 +84,7 @@ std::string SimpleThruster::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(thrust_b_); - str_tmp += WriteVector(torque_b_); + str_tmp += WriteVector(torque_b_Nm_); str_tmp += WriteScalar(CalcNorm(thrust_b_)); return str_tmp; diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 5468af7e3..36e5fa2d2 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -96,7 +96,7 @@ class SimpleThruster : public Component, public ILoggable { * @fn GetTorqueB * @brief Return generated torque on the body fixed frame [Nm] */ - inline const Vector<3> GetTorqueB() const { return torque_b_; }; + inline const Vector<3> GetTorqueB() const { return torque_b_Nm_; }; // Setter /** @@ -116,8 +116,8 @@ class SimpleThruster : public Component, public ILoggable { libra::NormalRand mag_nr_; //!< Normal random for thrust magnitude error libra::NormalRand dir_nr_; //!< Normal random for thrust direction error // outputs - Vector<3> thrust_b_{0.0}; //!< Generated thrust on the body fixed frame [N] - Vector<3> torque_b_{0.0}; //!< Generated torque on the body fixed frame [N] + Vector<3> thrust_b_{0.0}; //!< Generated thrust on the body fixed frame [N] + Vector<3> torque_b_Nm_{0.0}; //!< Generated torque on the body fixed frame [N] /** * @fn CalcThrust From 35098218435c642b52095198e0f3b6f9c72f763c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:25:15 +0100 Subject: [PATCH 0794/1086] Fix function argument names --- src/components/base/sensor.hpp | 6 +- .../base/sensor_template_functions.hpp | 9 +-- .../real/aocs/initialize_magnetorquer.cpp | 66 ++++++++++--------- .../real/aocs/initialize_magnetorquer.hpp | 8 +-- src/components/real/aocs/magnetorquer.cpp | 43 ++++++------ src/components/real/aocs/magnetorquer.hpp | 56 ++++++++-------- src/components/real/aocs/sun_sensor.cpp | 14 ++-- src/components/real/aocs/sun_sensor.hpp | 14 ++-- .../local/initialize_local_environment.cpp | 8 +-- 9 files changed, 117 insertions(+), 107 deletions(-) diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index 80a3dbe12..67fe6019d 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -25,14 +25,14 @@ class Sensor { * @param [in] scale_factor: Scale factor matrix * @param [in] range_to_const_c: Output range limit to be constant output value at the component frame * @param [in] range_to_zero_c: Output range limit to be zero output value at the component frame - * @param [in] bias_c: Constant bias noise at the component frame + * @param [in] bias_noise_c_Am2_: Constant bias noise at the component frame * @param [in] normal_random_standard_deviation_c: Standard deviation of normal random noise at the component frame * @param [in] random_walk_step_width_s: Step width for random walk calculation [sec] * @param [in] random_walk_standard_deviation_c: Standard deviation of random wark at the component frame * @param [in] random_walk_limit_c: Limit of random walk at the component frame */ Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, + const libra::Vector& bias_noise_c_Am2_, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c); /** * @fn ~Sensor @@ -53,7 +53,7 @@ class Sensor { libra::Matrix scale_factor_; //!< Scale factor matrix libra::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame libra::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame - libra::Vector bias_c_Am2_; //!< Constant bias noise at the component frame + libra::Vector bias_noise_c_Am2_; //!< Constant bias noise at the component frame libra::NormalRand normal_random_noise_c_[N]; //!< Normal random RandomWalk random_walk_noise_c_; //!< Random Walk diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index a10303059..db9ff2b2f 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -10,12 +10,13 @@ template Sensor::Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, - const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c) + const libra::Vector& bias_noise_c_Am2_, const libra::Vector& normal_random_standard_deviation_c, + const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, + const libra::Vector& random_walk_limit_c) : scale_factor_(scale_factor), range_to_const_c_(range_to_const_c), range_to_zero_c_(range_to_zero_c), - bias_c_Am2_(bias_c), + bias_noise_c_Am2_(bias_noise_c_Am2_), random_walk_noise_c_(random_walk_step_width_s, random_walk_standard_deviation_c, random_walk_limit_c) { for (size_t i = 0; i < N; i++) { normal_random_noise_c_[i].SetParameters(0.0, normal_random_standard_deviation_c[i], global_randomization.MakeSeed()); @@ -30,7 +31,7 @@ template libra::Vector Sensor::Measure(const libra::Vector true_value_c) { libra::Vector calc_value_c; calc_value_c = scale_factor_ * true_value_c; - calc_value_c += bias_c_Am2_; + calc_value_c += bias_noise_c_Am2_; for (size_t i = 0; i < N; ++i) { calc_value_c[i] += random_walk_noise_c_[i]; calc_value_c[i] += normal_random_noise_c_[i]; diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 97800a771..5597b142d 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -7,7 +7,7 @@ #include "library/initialize/initialize_file_access.hpp" MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* mag_env) { + const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -28,30 +28,31 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_c; - magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); + Vector max_magnetic_moment_c_Am2; + magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_c; - magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_c); + Vector min_magnetic_moment_c_Am2; + magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_c; - magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_c); + Vector bias_noise_c_Am2_; + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", rw_stddev_c); - Vector rw_limit_c; - magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", rw_limit_c); - Vector nr_stddev_c; - magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); + double random_walk_step_width_s = compo_step_time * (double)prescaler; + Vector random_walk_standard_deviation_c_Am2; + magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); + Vector random_walk_limit_c_Am2; + magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); + Vector normal_random_standard_deviation_c_Am2; + magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); - MagTorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, rw_stddev_c, - rw_limit_c, nr_stddev_c, mag_env); + MagTorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, + bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, + normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* mag_env) { + const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -72,27 +73,28 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_c; - magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_c); + Vector max_magnetic_moment_c_Am2; + magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_c; - magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_c); + Vector min_magnetic_moment_c_Am2; + magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_c; - magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_c); + Vector bias_noise_c_Am2_; + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); - double rw_stepwidth = compo_step_time * (double)prescaler; - Vector rw_stddev_c; - magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", rw_stddev_c); - Vector rw_limit_c; - magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", rw_limit_c); - Vector nr_stddev_c; - magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", nr_stddev_c); + double random_walk_step_width_s = compo_step_time * (double)prescaler; + Vector random_walk_standard_deviation_c_Am2; + magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); + Vector random_walk_limit_c_Am2; + magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); + Vector normal_random_standard_deviation_c_Am2; + magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); // PowerPort power_port->InitializeWithInitializeFile(fname); - MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_c, min_c, bias_c, rw_stepwidth, - rw_stddev_c, rw_limit_c, nr_stddev_c, mag_env); + MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, + min_magnetic_moment_c_Am2, bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, + random_walk_limit_c_Am2, normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index 40efd3589..cc1ec60ba 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -15,10 +15,10 @@ * @param [in] actuator_id: Actuator ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] - * @param [in] mag_env: Geomegnetic environment + * @param [in] geomagnetic_field: Geomegnetic environment */ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* mag_env); + const GeomagneticField* geomagnetic_field); /** * @fn InitMagTorquer * @brief Initialize functions for magnetometer with power port @@ -27,9 +27,9 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons * @param [in] actuator_id: Actuator ID * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] - * @param [in] mag_env: Geomegnetic environment + * @param [in] geomagnetic_field: Geomegnetic environment */ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* mag_env); + const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 09cc1fc38..5a6e192a3 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -11,41 +11,44 @@ #include MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Quaternion& quaternion_b2c, - const libra::Matrix& scale_factor, const libra::Vector& max_c, const libra::Vector& min_c, - const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env) + const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, + const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, + double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, + const libra::Vector& random_walk_limit_c_Am2, const libra::Vector& normal_random_standard_deviation_c_Am2, + const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), quaternion_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), - max_magnetic_moment_c_Am2_(max_c), - min_magnetic_moment_c_Am2_(min_c), - bias_c_Am2_(bias_c), - random_walk_c_Am2_(rw_stepwidth, rw_stddev_c, rw_limit_c), - geomagnetic_field_(mag_env) { + max_magnetic_moment_c_Am2_(max_magnetic_moment_c_Am2), + min_magnetic_moment_c_Am2_(min_magnetic_moment_c_Am2), + bias_noise_c_Am2_(bias_noise_c_Am2_), + random_walk_c_Am2_(random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2), + geomagnetic_field_(geomagnetic_field) { for (size_t i = 0; i < kMtqDim; i++) { - random_noise_c_Am2_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + random_noise_c_Am2_[i].SetParameters(0.0, normal_random_standard_deviation_c_Am2[i]); // global_randomization.MakeSeed() } } MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_c, - const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, - const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, - const GeomagneticField* mag_env) + const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, + const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, + const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c_Am2, const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), quaternion_c2b_(quaternion_b2c_.Conjugate()), scale_factor_(scale_factor), - max_magnetic_moment_c_Am2_(max_c), - min_magnetic_moment_c_Am2_(min_c), - bias_c_Am2_(bias_c), - random_walk_c_Am2_(rw_stepwidth, rw_stddev_c, rw_limit_c), - geomagnetic_field_(mag_env) { + max_magnetic_moment_c_Am2_(max_magnetic_moment_c_Am2), + min_magnetic_moment_c_Am2_(min_magnetic_moment_c_Am2), + bias_noise_c_Am2_(bias_noise_c_Am2_), + random_walk_c_Am2_(random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2), + geomagnetic_field_(geomagnetic_field) { for (size_t i = 0; i < kMtqDim; i++) { - random_noise_c_Am2_[i].SetParameters(0.0, nr_stddev_c[i]); // global_randomization.MakeSeed() + random_noise_c_Am2_[i].SetParameters(0.0, normal_random_standard_deviation_c_Am2[i]); // global_randomization.MakeSeed() } } @@ -66,7 +69,7 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { output_magnetic_moment_c_Am2_[i] = min_magnetic_moment_c_Am2_[i]; } // Add noise - output_magnetic_moment_c_Am2_[i] += bias_c_Am2_[i]; + output_magnetic_moment_c_Am2_[i] += bias_noise_c_Am2_[i]; output_magnetic_moment_c_Am2_[i] += random_walk_c_Am2_[i]; output_magnetic_moment_c_Am2_[i] += random_noise_c_Am2_[i]; } diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 10e02b605..b354fdbad 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -31,20 +31,22 @@ class MagTorquer : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] component_id : Actuator ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] scale_facter: Scale factor matrix - * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] - * @param [in] min_c : Minimum magnetic moment in the component frame [Am2] - * @param [in] bias_c : Constant bias noise in the component frame [Am2] - * @param [in] rw_stepwidth_c : Step width for random walk dynamics [s] - * @param [in] rw_stddev_c: Standard deviation of random walk noise in the component frame [Am2] - * @param [in] rw_limit_c: Limit for random walk noise in the component frame [Am2] - * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] + * @param [in] scale_factor: Scale factor matrix + * @param [in] max_magnetic_moment_c_Am2 : Maximum magnetic moment in the component frame [Am2] + * @param [in] min_magnetic_moment_c_Am2 : Minimum magnetic moment in the component frame [Am2] + * @param [in] bias_noise_c_Am2_ : Constant bias noise in the component frame [Am2] + * @param [in] random_walk_step_width_s : Step width for random walk dynamics [s] + * @param [in] random_walk_standard_deviation_c_Am2: Standard deviation of random walk noise in the component frame [Am2] + * @param [in] random_walk_limit_c_Am2: Limit for random walk noise in the component frame [Am2] + * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] geomagnetic_field: Geomagnetic environment */ MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const libra::Matrix& scale_facter, const libra::Vector& max_c, const libra::Vector& min_c, - const libra::Vector& bias_c, double rw_stepwidth, const libra::Vector& rw_stddev_c, - const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, const GeomagneticField* mag_env); + const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, + const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, + double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, + const libra::Vector& random_walk_limit_c_Am2, const libra::Vector& normal_random_standard_deviation_c_Am2, + const GeomagneticField* geomagnetic_field); /** * @fn MagTorquer * @brief Constructor with power port @@ -53,21 +55,22 @@ class MagTorquer : public Component, public ILoggable { * @param [in] power_port: Power port * @param [in] component_id : Actuator ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] scale_facter: Scale factor matrix - * @param [in] max_c : Maximum magnetic moment in the component frame [Am2] - * @param [in] min_c : Minimum magnetic moment in the component frame [Am2] - * @param [in] bias_c : Constant bias noise in the component frame [Am2] - * @param [in] rw_stepwidth_c : Step width for random walk dynamics [s] - * @param [in] rw_stddev_c: Standard deviation of random walk noise in the component frame [Am2] - * @param [in] rw_limit_c: Limit for random walk noise in the component frame [Am2] - * @param [in] nr_stddev_c: Standard deviation for the normal random noise in the component frame [Am2] + * @param [in] scale_factor: Scale factor matrix + * @param [in] max_magnetic_moment_c_Am2 : Maximum magnetic moment in the component frame [Am2] + * @param [in] min_magnetic_moment_c_Am2 : Minimum magnetic moment in the component frame [Am2] + * @param [in] bias_noise_c_Am2_ : Constant bias noise in the component frame [Am2] + * @param [in] random_walk_step_width_s : Step width for random walk dynamics [s] + * @param [in] random_walk_standard_deviation_c_Am2: Standard deviation of random walk noise in the component frame [Am2] + * @param [in] random_walk_limit_c_Am2: Limit for random walk noise in the component frame [Am2] + * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] geomagnetic_field: Geomagnetic environment */ MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_facter, const libra::Vector& max_c, - const libra::Vector& min_c, const libra::Vector& bias_c, double rw_stepwidth, - const libra::Vector& rw_stddev_c, const libra::Vector& rw_limit_c, const libra::Vector& nr_stddev_c, - const GeomagneticField* mag_env); + const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, + const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, + const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c_Am2, const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field); // Override functions for Component /** @@ -121,9 +124,10 @@ class MagTorquer : public Component, public ILoggable { libra::Matrix scale_factor_; //!< Scale factor matrix libra::Vector max_magnetic_moment_c_Am2_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] libra::Vector min_magnetic_moment_c_Am2_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] - libra::Vector bias_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_[kMtqDim]; //!< Normal random noise + + libra::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_[kMtqDim]; //!< Normal random noise const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 83d2aec91..3ac1ed201 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -14,7 +14,7 @@ using libra::NormalRand; using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, + const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator), @@ -24,11 +24,11 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celes_info_(local_celes_info) { - Initialize(nr_stddev_c, nr_bias_stddev_c); + Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) : Component(prescaler, clock_generator, power_port), @@ -38,18 +38,18 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celes_info_(local_celes_info) { - Initialize(nr_stddev_c, nr_bias_stddev_c); + Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } -void SunSensor::Initialize(const double nr_stddev_c, const double nr_bias_stddev_c) { +void SunSensor::Initialize(const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c) { // Bias NormalRand nr(0.0, nr_bias_stddev_c, global_randomization.MakeSeed()); bias_alpha_ += nr; bias_beta_ += nr; // Normal Random - nrs_alpha_.SetParameters(0.0, nr_stddev_c); // global_randomization.MakeSeed() - nrs_beta_.SetParameters(0.0, nr_stddev_c); // global_randomization.MakeSeed() + nrs_alpha_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() + nrs_beta_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() } void SunSensor::MainRoutine(int count) { UNUSED(count); diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 583a83e8f..5a7de89bb 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -29,14 +29,14 @@ class SunSensor : public Component, public ILoggable { * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] - * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] + * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, + const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); /** @@ -48,15 +48,15 @@ class SunSensor : public Component, public ILoggable { * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] - * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] + * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celes_info: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double nr_stddev_c, const double nr_bias_stddev_c, - const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, + const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); // Override functions for Component @@ -130,10 +130,10 @@ class SunSensor : public Component, public ILoggable { /** * @fn TanRange * @brief Clip angle as tangent range - * @param [in] nr_stddev_c: Standard deviation of normal random noise in the component frame [rad] + * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] */ - void Initialize(const double nr_stddev_c, const double nr_bias_stddev_c); + void Initialize(const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c); /** * @fn CalcSolarIlluminance * @brief Calculate solar illuminance on the sun sensor surface diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index f22d1eaf4..0de817e30 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -20,11 +20,11 @@ GeomagneticField InitGeomagneticField(std::string initialize_file_path) { double mag_rwlimit = conf.ReadDouble(section, "magnetic_field_random_walk_limit_nT"); double mag_wnvar = conf.ReadDouble(section, "magnetic_field_white_noise_standard_deviation_nT"); - GeomagneticField mag_env(fname, mag_rwdev, mag_rwlimit, mag_wnvar); - mag_env.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); - mag_env.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); + GeomagneticField geomagnetic_field(fname, mag_rwdev, mag_rwlimit, mag_wnvar); + geomagnetic_field.IsCalcEnabled = conf.ReadEnable(section, CALC_LABEL); + geomagnetic_field.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); - return mag_env; + return geomagnetic_field; } SolarRadiationPressureEnvironment InitSolarRadiationPressureEnvironment(std::string initialize_file_path, From 92efcad7653685be5d75c8d6acd7a70a5ef0fd4a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:27:01 +0100 Subject: [PATCH 0795/1086] Fix public function name --- src/components/real/aocs/magnetorquer.hpp | 19 ++++++++++--------- .../sample_spacecraft/sample_components.cpp | 4 ++-- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index b354fdbad..7874f3f17 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -97,21 +97,22 @@ class MagTorquer : public Component, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetMagMoment_b - * @brief Return output magnetic moment in the body fixed frame [Am2] - */ - inline const libra::Vector& GetMagMoment_b(void) const { return output_magnetic_moment_b_Am2_; }; - /** - * @fn GetTorque_b + * @fn GetOutputTorque_b_Nm * @brief Return output torque in the body fixed frame [Nm] */ - inline const libra::Vector& GetTorque_b(void) const { return torque_b_Nm_; }; + inline const libra::Vector& GetOutputTorque_b_Nm(void) const { return torque_b_Nm_; }; /** - * @fn SetMagMomentC + * @fn SetOutputMagneticMoment_c_Am2 * @brief Set output magnetic moment in the component frame [Am2] */ - inline void SetMagMomentC(const libra::Vector mag_moment_c) { output_magnetic_moment_c_Am2_ = mag_moment_c; }; + inline void SetOutputMagneticMoment_c_Am2(const libra::Vector mag_moment_c) { output_magnetic_moment_c_Am2_ = mag_moment_c; }; + + /** + * @fn SetOutputMagneticMoment_b_Am2 + * @brief Return output magnetic moment in the body fixed frame [Am2] + */ + inline const libra::Vector& SetOutputMagneticMoment_b_Am2(void) const { return output_magnetic_moment_b_Am2_; }; protected: const int component_id_ = 0; //!< Actuator ID diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 2733501f3..4a5e90f8f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -107,7 +107,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // actuator debug output // libra::Vector mag_moment_c{0.01}; - // mag_torquer_->SetMagMomentC(mag_moment_c); + // mag_torquer_->SetOutputMagneticMoment_c_Am2(mag_moment_c); // rw_->SetTargetTorqueRw(0.01); // rw_->SetDriveFlag(true); // thruster_->SetDuty(0.9); @@ -158,7 +158,7 @@ libra::Vector<3> SampleComponents::GenerateForce_N_b() { libra::Vector<3> SampleComponents::GenerateTorque_Nm_b() { libra::Vector<3> torque_Nm_b_(0.0); - torque_Nm_b_ += mag_torquer_->GetTorque_b(); + torque_Nm_b_ += mag_torquer_->GetOutputTorque_b_Nm(); torque_Nm_b_ += rw_->GetOutputTorqueB(); torque_Nm_b_ += thruster_->GetTorqueB(); torque_Nm_b_ += torque_generator_->GetGeneratedTorque_b_Nm(); From c4ad8dbc8d64f9784047417a5b985aedadbd68a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:29:36 +0100 Subject: [PATCH 0796/1086] Fix power off routine --- src/components/real/aocs/magnetorquer.cpp | 10 +++++++--- src/components/real/aocs/magnetorquer.hpp | 2 +- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 5a6e192a3..0df7310a5 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -52,13 +52,17 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, Pow } } -void MagTorquer::MainRoutine(int count) { - UNUSED(count); +void MagTorquer::MainRoutine(const int time_count) { + UNUSED(time_count); CalcOutputTorque(); } -void MagTorquer::PowerOffRoutine() { torque_b_Nm_ *= 0.0; } +void MagTorquer::PowerOffRoutine() { + torque_b_Nm_ *= 0.0; + output_magnetic_moment_c_Am2_ *= 0.0; + output_magnetic_moment_b_Am2_ *= 0.0; +} libra::Vector MagTorquer::CalcOutputTorque(void) { for (size_t i = 0; i < kMtqDim; ++i) { diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 7874f3f17..0aeeadb51 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -77,7 +77,7 @@ class MagTorquer : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to output torque */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; /** * @fn PowerOffRoutine * @brief Power off routine to stop actuation From 680195dd39016d5a8f48468a5339b08c9232e994 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:31:34 +0100 Subject: [PATCH 0797/1086] Rename MagTorquer to Magnetorquer --- .../real/aocs/initialize_magnetorquer.cpp | 64 ++++++++--------- .../real/aocs/initialize_magnetorquer.hpp | 8 +-- src/components/real/aocs/magnetorquer.cpp | 46 +++++++------ src/components/real/aocs/magnetorquer.hpp | 68 +++++++++---------- .../sample_spacecraft/sample_components.cpp | 8 +-- .../sample_spacecraft/sample_components.hpp | 4 +- 6 files changed, 100 insertions(+), 98 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 5597b142d..804368291 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -6,8 +6,8 @@ #include "library/initialize/initialize_file_access.hpp" -MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -16,43 +16,43 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Vector sf_vec; + Vector sf_vec; magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kMtqDim; i++) { - for (size_t j = 0; j < kMtqDim; j++) { - scale_factor[i][j] = sf_vec[i * kMtqDim + j]; + Matrix scale_factor; + for (size_t i = 0; i < kMtqDimension; i++) { + for (size_t j = 0; j < kMtqDimension; j++) { + scale_factor[i][j] = sf_vec[i * kMtqDimension + j]; } } Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_magnetic_moment_c_Am2; + Vector max_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_magnetic_moment_c_Am2; + Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_noise_c_Am2_; + Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); double random_walk_step_width_s = compo_step_time * (double)prescaler; - Vector random_walk_standard_deviation_c_Am2; + Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); - Vector random_walk_limit_c_Am2; + Vector random_walk_limit_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); - Vector normal_random_standard_deviation_c_Am2; + Vector normal_random_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); - MagTorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, - bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, - normal_random_standard_deviation_c_Am2, geomagnetic_field); + Magnetorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, + bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, + normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } -MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(fname); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -61,40 +61,40 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Vector sf_vec; + Vector sf_vec; magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); - Matrix scale_factor; - for (size_t i = 0; i < kMtqDim; i++) { - for (size_t j = 0; j < kMtqDim; j++) { - scale_factor[i][j] = sf_vec[i * kMtqDim + j]; + Matrix scale_factor; + for (size_t i = 0; i < kMtqDimension; i++) { + for (size_t j = 0; j < kMtqDimension; j++) { + scale_factor[i][j] = sf_vec[i * kMtqDimension + j]; } } Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_magnetic_moment_c_Am2; + Vector max_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_magnetic_moment_c_Am2; + Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_noise_c_Am2_; + Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); double random_walk_step_width_s = compo_step_time * (double)prescaler; - Vector random_walk_standard_deviation_c_Am2; + Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); - Vector random_walk_limit_c_Am2; + Vector random_walk_limit_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); - Vector normal_random_standard_deviation_c_Am2; + Vector normal_random_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); // PowerPort power_port->InitializeWithInitializeFile(fname); - MagTorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, - min_magnetic_moment_c_Am2, bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, - random_walk_limit_c_Am2, normal_random_standard_deviation_c_Am2, geomagnetic_field); + Magnetorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, + min_magnetic_moment_c_Am2, bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, + random_walk_limit_c_Am2, normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index cc1ec60ba..edf9bf5e9 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -17,8 +17,8 @@ * @param [in] compo_step_time: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field); +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field); /** * @fn InitMagTorquer * @brief Initialize functions for magnetometer with power port @@ -29,7 +29,7 @@ MagTorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, cons * @param [in] compo_step_time: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -MagTorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field); +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, + const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 0df7310a5..23d0e4f86 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -10,12 +10,13 @@ #include #include -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Quaternion& quaternion_b2c, - const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, - const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, - double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, - const libra::Vector& random_walk_limit_c_Am2, const libra::Vector& normal_random_standard_deviation_c_Am2, - const GeomagneticField* geomagnetic_field) +Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Quaternion& quaternion_b2c, + const libra::Matrix& scale_factor, + const libra::Vector& max_magnetic_moment_c_Am2, + const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, + double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, + const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -26,17 +27,18 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, con bias_noise_c_Am2_(bias_noise_c_Am2_), random_walk_c_Am2_(random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2), geomagnetic_field_(geomagnetic_field) { - for (size_t i = 0; i < kMtqDim; i++) { + for (size_t i = 0; i < kMtqDimension; i++) { random_noise_c_Am2_[i].SetParameters(0.0, normal_random_standard_deviation_c_Am2[i]); // global_randomization.MakeSeed() } } -MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, - const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, - const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, - const libra::Vector& random_walk_standard_deviation_c_Am2, const libra::Vector& random_walk_limit_c_Am2, - const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field) +Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, + const libra::Vector& max_magnetic_moment_c_Am2, + const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, + double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, + const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -47,25 +49,25 @@ MagTorquer::MagTorquer(const int prescaler, ClockGenerator* clock_generator, Pow bias_noise_c_Am2_(bias_noise_c_Am2_), random_walk_c_Am2_(random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2), geomagnetic_field_(geomagnetic_field) { - for (size_t i = 0; i < kMtqDim; i++) { + for (size_t i = 0; i < kMtqDimension; i++) { random_noise_c_Am2_[i].SetParameters(0.0, normal_random_standard_deviation_c_Am2[i]); // global_randomization.MakeSeed() } } -void MagTorquer::MainRoutine(const int time_count) { +void Magnetorquer::MainRoutine(const int time_count) { UNUSED(time_count); CalcOutputTorque(); } -void MagTorquer::PowerOffRoutine() { +void Magnetorquer::PowerOffRoutine() { torque_b_Nm_ *= 0.0; output_magnetic_moment_c_Am2_ *= 0.0; output_magnetic_moment_b_Am2_ *= 0.0; } -libra::Vector MagTorquer::CalcOutputTorque(void) { - for (size_t i = 0; i < kMtqDim; ++i) { +libra::Vector Magnetorquer::CalcOutputTorque(void) { + for (size_t i = 0; i < kMtqDimension; ++i) { // Limit Check if (output_magnetic_moment_c_Am2_[i] > max_magnetic_moment_c_Am2_[i]) { output_magnetic_moment_c_Am2_[i] = max_magnetic_moment_c_Am2_[i]; @@ -89,18 +91,18 @@ libra::Vector MagTorquer::CalcOutputTorque(void) { return torque_b_Nm_; } -std::string MagTorquer::GetLogHeader() const { +std::string Magnetorquer::GetLogHeader() const { std::string str_tmp = ""; const std::string actuator_id = std::to_string(static_cast(component_id_)); std::string actuator_name = "magnetorquer" + actuator_id + "_"; - str_tmp += WriteVector(actuator_name + "output_magnetic_moment", "b", "Am2", kMtqDim); - str_tmp += WriteVector(actuator_name + "output_torque", "b", "Nm", kMtqDim); + str_tmp += WriteVector(actuator_name + "output_magnetic_moment", "b", "Am2", kMtqDimension); + str_tmp += WriteVector(actuator_name + "output_torque", "b", "Nm", kMtqDimension); return str_tmp; } -std::string MagTorquer::GetLogValue() const { +std::string Magnetorquer::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteVector(output_magnetic_moment_b_Am2_); str_tmp += WriteVector(torque_b_Nm_); diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index 0aeeadb51..b08564297 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -16,16 +16,16 @@ #include "../../base/component.hpp" -const size_t kMtqDim = 3; //!< Dimension of magnetorquer +const size_t kMtqDimension = 3; //!< Dimension of magnetorquer /** - * @class MagTorquer + * @class Magnetorquer * @brief Class to emulate magnetorquer */ -class MagTorquer : public Component, public ILoggable { +class Magnetorquer : public Component, public ILoggable { public: /** - * @fn MagTorquer + * @fn Magnetorquer * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -41,14 +41,14 @@ class MagTorquer : public Component, public ILoggable { * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] geomagnetic_field: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, - const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, - double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, - const libra::Vector& random_walk_limit_c_Am2, const libra::Vector& normal_random_standard_deviation_c_Am2, - const GeomagneticField* geomagnetic_field); + Magnetorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, + const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, + const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, + double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, + const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field); /** - * @fn MagTorquer + * @fn Magnetorquer * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -65,12 +65,12 @@ class MagTorquer : public Component, public ILoggable { * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation for the normal random noise in the component frame [Am2] * @param [in] geomagnetic_field: Geomagnetic environment */ - MagTorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, - const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, - const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, - const libra::Vector& random_walk_standard_deviation_c_Am2, const libra::Vector& random_walk_limit_c_Am2, - const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field); + Magnetorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, + const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, + const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, + const libra::Vector& random_walk_standard_deviation_c_Am2, const libra::Vector& random_walk_limit_c_Am2, + const libra::Vector& normal_random_standard_deviation_c_Am2, const GeomagneticField* geomagnetic_field); // Override functions for Component /** @@ -100,35 +100,35 @@ class MagTorquer : public Component, public ILoggable { * @fn GetOutputTorque_b_Nm * @brief Return output torque in the body fixed frame [Nm] */ - inline const libra::Vector& GetOutputTorque_b_Nm(void) const { return torque_b_Nm_; }; + inline const libra::Vector& GetOutputTorque_b_Nm(void) const { return torque_b_Nm_; }; /** * @fn SetOutputMagneticMoment_c_Am2 * @brief Set output magnetic moment in the component frame [Am2] */ - inline void SetOutputMagneticMoment_c_Am2(const libra::Vector mag_moment_c) { output_magnetic_moment_c_Am2_ = mag_moment_c; }; + inline void SetOutputMagneticMoment_c_Am2(const libra::Vector mag_moment_c) { output_magnetic_moment_c_Am2_ = mag_moment_c; }; /** * @fn SetOutputMagneticMoment_b_Am2 * @brief Return output magnetic moment in the body fixed frame [Am2] */ - inline const libra::Vector& SetOutputMagneticMoment_b_Am2(void) const { return output_magnetic_moment_b_Am2_; }; + inline const libra::Vector& SetOutputMagneticMoment_b_Am2(void) const { return output_magnetic_moment_b_Am2_; }; protected: - const int component_id_ = 0; //!< Actuator ID - const double kConvertNanoT2T = 1.0e-9; //!< Constant to convert nT to T - libra::Vector torque_b_Nm_{0.0}; //!< Output torque in the body fixed frame [Nm] - libra::Vector output_magnetic_moment_c_Am2_{0.0}; //!< Output output magnetic moment in the component frame [Am2] - libra::Vector output_magnetic_moment_b_Am2_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] - libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame - libra::Quaternion quaternion_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame - libra::Matrix scale_factor_; //!< Scale factor matrix - libra::Vector max_magnetic_moment_c_Am2_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] - libra::Vector min_magnetic_moment_c_Am2_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] + const int component_id_ = 0; //!< Actuator ID + const double kConvertNanoT2T = 1.0e-9; //!< Constant to convert nT to T + libra::Vector torque_b_Nm_{0.0}; //!< Output torque in the body fixed frame [Nm] + libra::Vector output_magnetic_moment_c_Am2_{0.0}; //!< Output output magnetic moment in the component frame [Am2] + libra::Vector output_magnetic_moment_b_Am2_{0.0}; //!< Output output magnetic moment in the body fixed frame [Am2] + libra::Quaternion quaternion_b2c_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from body frame to component frame + libra::Quaternion quaternion_c2b_{0.0, 0.0, 0.0, 1.0}; //!< Quaternion from component frame to body frame + libra::Matrix scale_factor_; //!< Scale factor matrix + libra::Vector max_magnetic_moment_c_Am2_{100.0}; //!< Maximum magnetic moment in the component frame [Am2] + libra::Vector min_magnetic_moment_c_Am2_{-100.0}; //!< Minimum magnetic moment in the component frame [Am2] - libra::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_[kMtqDim]; //!< Normal random noise + libra::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 const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment @@ -137,7 +137,7 @@ class MagTorquer : public Component, public ILoggable { * @brief Calculate output torque * @return Output torque in the body fixed frame [Nm] */ - libra::Vector CalcOutputTorque(void); + libra::Vector CalcOutputTorque(void); }; #endif // S2E_COMPONENTS_REAL_AOCS_MAGNETORQUER_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 4a5e90f8f..c37c044d8 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -53,11 +53,11 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur gnss_ = new GnssReceiver( InitGnssReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); - // MagTorquer + // Magnetorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_torquer_ = new MagTorquer(InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - &(local_env_->GetGeomagneticField()))); + mag_torquer_ = new Magnetorquer(InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, + glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); @@ -106,7 +106,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur /**************/ // actuator debug output - // libra::Vector mag_moment_c{0.01}; + // libra::Vector mag_moment_c{0.01}; // mag_torquer_->SetOutputMagneticMoment_c_Am2(mag_moment_c); // rw_->SetTargetTorqueRw(0.01); // rw_->SetDriveFlag(true); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 2b8ef858c..448accb27 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -37,7 +37,7 @@ class Magnetometer; class STT; class SunSensor; class GnssReceiver; -class MagTorquer; +class Magnetorquer; class RWModel; class SimpleThruster; class ForceGenerator; @@ -92,7 +92,7 @@ class SampleComponents : public InstalledComponents { STT* stt_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor GnssReceiver* gnss_; //!< GNSS receiver - MagTorquer* mag_torquer_; //!< Magnetorquer + Magnetorquer* mag_torquer_; //!< Magnetorquer RWModel* rw_; //!< Reaction Wheel SimpleThruster* thruster_; //!< Thruster ForceGenerator* force_generator_; //!< Ideal Force Generator From 9de57cbd216eefa3624f3a832f0f673502ceea4f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:36:23 +0100 Subject: [PATCH 0798/1086] Fix private function and variables name --- src/components/real/aocs/reaction_wheel.cpp | 2 +- .../real/aocs/reaction_wheel_jitter.cpp | 84 +++++++++---------- .../real/aocs/reaction_wheel_jitter.hpp | 36 ++++---- 3 files changed, 61 insertions(+), 61 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 2b920599a..c5c485805 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -152,7 +152,7 @@ libra::Vector<3> RWModel::CalcTorque() { const libra::Vector<3> RWModel::GetOutputTorqueB() const { if (is_calculated_jitter_) { - // Add jitter_force_b_-derived torque and jitter_torque_b_ to output_torqur_b + // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torqur_b return output_torque_b_ - libra::OuterProduct(pos_b_, rw_jitter_.GetJitterForceB()) - rw_jitter_.GetJitterTorqueB(); } else { return output_torque_b_; diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 39e045cdf..27251fe11 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -11,12 +11,12 @@ RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, const double jitter_update_interval, const libra::Quaternion quaternion_b2c, const double structural_resonance_freq, const double damping_factor, const double bandwidth, const bool considers_structural_resonance) - : radial_force_harmonics_coef_(radial_force_harmonics_coef), - radial_torque_harmonics_coef_(radial_torque_harmonics_coef), - jitter_update_interval_(jitter_update_interval), + : radial_force_harmonics_coefficients_(radial_force_harmonics_coef), + radial_torque_harmonics_coefficients_(radial_torque_harmonics_coef), + update_interval_s_(jitter_update_interval), quaternion_b2c_(quaternion_b2c), - structural_resonance_freq_(structural_resonance_freq), - structural_resonance_angular_freq_(libra::tau * structural_resonance_freq), + structural_resonance_frequency_Hz_(structural_resonance_freq), + structural_resonance_angular_frequency_Hz_(libra::tau * structural_resonance_freq), damping_factor_(damping_factor), bandwidth_(bandwidth), considers_structural_resonance_(considers_structural_resonance) { @@ -25,15 +25,15 @@ RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::default_random_engine engine(seed_gen()); std::uniform_real_distribution dist(0.0, libra::tau); // Initialize RW rotation phase - for (size_t i = 0; i < radial_force_harmonics_coef_.size(); i++) { - jitter_force_rot_phase_.push_back(dist(engine)); + for (size_t i = 0; i < radial_force_harmonics_coefficients_.size(); i++) { + jitter_force_rotation_phase_.push_back(dist(engine)); } - for (size_t i = 0; i < radial_torque_harmonics_coef_.size(); i++) { - jitter_torque_rot_phase_.push_back(dist(engine)); + for (size_t i = 0; i < radial_torque_harmonics_coefficients_.size(); i++) { + jitter_torque_rotation_phase_.push_back(dist(engine)); } // Calculate the coefficients of the difference equation when structural resonance is considered if (considers_structural_resonance_) { - CalcCoef(); + CalcCoefficients(); } } @@ -45,52 +45,52 @@ void RWJitter::CalcJitter(double angular_velocity_rad) { unfiltered_jitter_torque_n_c_ *= 0.0; // Calculate harmonics force - for (size_t i = 0; i < jitter_force_rot_phase_.size(); i++) { + for (size_t i = 0; i < jitter_force_rotation_phase_.size(); i++) { // Advance the phase of RW rotation - jitter_force_rot_phase_[i] += radial_force_harmonics_coef_[i][0] * angular_velocity_rad * jitter_update_interval_; + jitter_force_rotation_phase_[i] += radial_force_harmonics_coefficients_[i][0] * angular_velocity_rad * update_interval_s_; // Add jitter force unfiltered_jitter_force_n_c_[0] += - radial_force_harmonics_coef_[i][1] * angular_velocity_rad * angular_velocity_rad * sin(jitter_force_rot_phase_[i]); + radial_force_harmonics_coefficients_[i][1] * angular_velocity_rad * angular_velocity_rad * sin(jitter_force_rotation_phase_[i]); unfiltered_jitter_force_n_c_[1] += - radial_force_harmonics_coef_[i][1] * angular_velocity_rad * angular_velocity_rad * cos(jitter_force_rot_phase_[i]); + radial_force_harmonics_coefficients_[i][1] * angular_velocity_rad * angular_velocity_rad * cos(jitter_force_rotation_phase_[i]); // jitter_force_c_[2] += 0.0; } // Calculate harmonics torque - for (size_t i = 0; i < jitter_torque_rot_phase_.size(); i++) { + for (size_t i = 0; i < jitter_torque_rotation_phase_.size(); i++) { // Advance the phase of RW rotation - jitter_torque_rot_phase_[i] += radial_torque_harmonics_coef_[i][0] * angular_velocity_rad * jitter_update_interval_; + jitter_torque_rotation_phase_[i] += radial_torque_harmonics_coefficients_[i][0] * angular_velocity_rad * update_interval_s_; // Add jitter torque unfiltered_jitter_torque_n_c_[0] += - radial_torque_harmonics_coef_[i][1] * angular_velocity_rad * angular_velocity_rad * sin(jitter_torque_rot_phase_[i]); + radial_torque_harmonics_coefficients_[i][1] * angular_velocity_rad * angular_velocity_rad * sin(jitter_torque_rotation_phase_[i]); unfiltered_jitter_torque_n_c_[1] += - radial_torque_harmonics_coef_[i][1] * angular_velocity_rad * angular_velocity_rad * cos(jitter_torque_rot_phase_[i]); + radial_torque_harmonics_coefficients_[i][1] * angular_velocity_rad * angular_velocity_rad * cos(jitter_torque_rotation_phase_[i]); // jitter_torque_c_[2] += 0.0; } // Add structural resonance if (considers_structural_resonance_) { AddStructuralResonance(); - jitter_force_b_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_force_n_c_); - jitter_torque_b_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_torque_n_c_); + jitter_force_b_N_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_force_n_c_); + jitter_torque_b_Nm_ = quaternion_b2c_.InverseFrameConversion(filtered_jitter_torque_n_c_); } else { - jitter_force_b_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_force_n_c_); - jitter_torque_b_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_torque_n_c_); + jitter_force_b_N_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_force_n_c_); + jitter_torque_b_Nm_ = quaternion_b2c_.InverseFrameConversion(unfiltered_jitter_torque_n_c_); } } void RWJitter::AddStructuralResonance() { // Solve difference equations for (int i = 0; i < 3; i++) { - filtered_jitter_force_n_c_[i] = - (-coef_[1] * filtered_jitter_force_n_1_c_[i] - coef_[2] * filtered_jitter_force_n_2_c_[i] + coef_[3] * unfiltered_jitter_force_n_c_[i] + - coef_[4] * unfiltered_jitter_force_n_1_c_[i] + coef_[5] * unfiltered_jitter_force_n_2_c_[i]) / - coef_[0]; + filtered_jitter_force_n_c_[i] = (-coefficients_[1] * filtered_jitter_force_n_1_c_[i] - coefficients_[2] * filtered_jitter_force_n_2_c_[i] + + coefficients_[3] * unfiltered_jitter_force_n_c_[i] + coefficients_[4] * unfiltered_jitter_force_n_1_c_[i] + + coefficients_[5] * unfiltered_jitter_force_n_2_c_[i]) / + coefficients_[0]; - filtered_jitter_torque_n_c_[i] = - (-coef_[1] * filtered_jitter_torque_n_1_c_[i] - coef_[2] * filtered_jitter_torque_n_2_c_[i] + coef_[3] * unfiltered_jitter_torque_n_c_[i] + - coef_[4] * unfiltered_jitter_torque_n_1_c_[i] + coef_[5] * unfiltered_jitter_torque_n_2_c_[i]) / - coef_[0]; + filtered_jitter_torque_n_c_[i] = (-coefficients_[1] * filtered_jitter_torque_n_1_c_[i] - coefficients_[2] * filtered_jitter_torque_n_2_c_[i] + + coefficients_[3] * unfiltered_jitter_torque_n_c_[i] + coefficients_[4] * unfiltered_jitter_torque_n_1_c_[i] + + coefficients_[5] * unfiltered_jitter_torque_n_2_c_[i]) / + coefficients_[0]; } ShiftTimeStep(); @@ -108,18 +108,18 @@ void RWJitter::ShiftTimeStep() { filtered_jitter_torque_n_1_c_ = filtered_jitter_torque_n_c_; } -void RWJitter::CalcCoef() { +void RWJitter::CalcCoefficients() { // Pre-warping - structural_resonance_angular_freq_ = 2.0 / jitter_update_interval_ * tan(structural_resonance_angular_freq_ * jitter_update_interval_ / 2.0); + structural_resonance_angular_frequency_Hz_ = 2.0 / update_interval_s_ * tan(structural_resonance_angular_frequency_Hz_ * update_interval_s_ / 2.0); // Calculate coefficients of difference equation - coef_[0] = 4.0 + 4.0 * bandwidth_ * damping_factor_ * jitter_update_interval_ * structural_resonance_angular_freq_ + - pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); - coef_[1] = -8.0 + 2.0 * pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); - coef_[2] = 4.0 - 4.0 * bandwidth_ * damping_factor_ * jitter_update_interval_ * structural_resonance_angular_freq_ + - pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); - coef_[3] = 4.0 + 4.0 * damping_factor_ * jitter_update_interval_ * structural_resonance_angular_freq_ + - pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); - coef_[4] = -8.0 + 2.0 * pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); - coef_[5] = 4.0 - 4.0 * damping_factor_ * jitter_update_interval_ * structural_resonance_angular_freq_ + - pow(jitter_update_interval_, 2.0) * pow(structural_resonance_angular_freq_, 2.0); + coefficients_[0] = 4.0 + 4.0 * bandwidth_ * damping_factor_ * update_interval_s_ * structural_resonance_angular_frequency_Hz_ + + pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); + coefficients_[1] = -8.0 + 2.0 * pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); + coefficients_[2] = 4.0 - 4.0 * bandwidth_ * damping_factor_ * update_interval_s_ * structural_resonance_angular_frequency_Hz_ + + pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); + coefficients_[3] = 4.0 + 4.0 * damping_factor_ * update_interval_s_ * structural_resonance_angular_frequency_Hz_ + + pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); + coefficients_[4] = -8.0 + 2.0 * pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); + coefficients_[5] = 4.0 - 4.0 * damping_factor_ * update_interval_s_ * structural_resonance_angular_frequency_Hz_ + + pow(update_interval_s_, 2.0) * pow(structural_resonance_angular_frequency_Hz_, 2.0); } diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 54fcca2c4..39a800609 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -49,12 +49,12 @@ class RWJitter { * @fn GetJitterForceB * @brief Return generated jitter force in the body fixed frame [N] */ - const libra::Vector<3> GetJitterForceB() const { return jitter_force_b_; } + const libra::Vector<3> GetJitterForceB() const { return jitter_force_b_N_; } /** * @fn GetJitterTorqueB * @brief Return generated jitter torque in the body fixed frame [Nm] */ - const libra::Vector<3> GetJitterTorqueB() const { return jitter_torque_b_; } + const libra::Vector<3> GetJitterTorqueB() const { return jitter_torque_b_Nm_; } /** * @fn GetJitterForceC * @brief Return generated jitter force in the components frame [N] @@ -71,21 +71,21 @@ class RWJitter { } private: - std::vector> radial_force_harmonics_coef_; //!< Coefficients for radial force harmonics - std::vector> radial_torque_harmonics_coef_; //!< Coefficients for radial torque harmonics + std::vector> radial_force_harmonics_coefficients_; //!< Coefficients for radial force harmonics + std::vector> radial_torque_harmonics_coefficients_; //!< Coefficients for radial torque harmonics - const double jitter_update_interval_; //!< Jitter update interval [sec] - libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame + const double update_interval_s_; //!< Jitter update interval [sec] + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame - double structural_resonance_freq_; //!< Frequency of structural resonance [Hz] - double structural_resonance_angular_freq_; //!< Angular Frequency of structural resonance - double damping_factor_; //!< Damping factor of structural resonance - double bandwidth_; //!< Bandwidth of structural resonance - bool considers_structural_resonance_; //!< Flag to consider structural resonance + double structural_resonance_frequency_Hz_; //!< Frequency of structural resonance [Hz] + double structural_resonance_angular_frequency_Hz_; //!< Angular Frequency of structural resonance + double damping_factor_; //!< Damping factor of structural resonance + double bandwidth_; //!< Bandwidth of structural resonance + bool considers_structural_resonance_; //!< Flag to consider structural resonance // Jitter calculation variables - std::vector jitter_force_rot_phase_; //!< 2 * pi * h_i * Omega * t [rad] - std::vector jitter_torque_rot_phase_; //!< 2 * pi * h_i * Omega * t [rad] + std::vector jitter_force_rotation_phase_; //!< 2 * pi * h_i * Omega * t [rad] + std::vector jitter_torque_rotation_phase_; //!< 2 * pi * h_i * Omega * t [rad] // Variables for solving difference equations in compo frame libra::Vector<3> unfiltered_jitter_force_n_c_{0.0}; @@ -100,10 +100,10 @@ class RWJitter { libra::Vector<3> filtered_jitter_torque_n_c_{0.0}; libra::Vector<3> filtered_jitter_torque_n_1_c_{0.0}; libra::Vector<3> filtered_jitter_torque_n_2_c_{0.0}; - double coef_[6]; //!< Coefficients of difference equation + double coefficients_[6]; //!< Coefficients of difference equation - libra::Vector<3> jitter_force_b_{0.0}; //!< Generated jitter force in the body frame [N] - libra::Vector<3> jitter_torque_b_{0.0}; //!< Generated jitter torque in the body frame [Nm] + libra::Vector<3> jitter_force_b_N_{0.0}; //!< Generated jitter force in the body frame [N] + libra::Vector<3> jitter_torque_b_Nm_{0.0}; //!< Generated jitter torque in the body frame [Nm] /** * @fn AddStructuralResonance @@ -116,10 +116,10 @@ class RWJitter { */ void ShiftTimeStep(); /** - * @fn CalcCoef + * @fn CalcCoefficients * @brief Calculation coefficients */ - void CalcCoef(); + void CalcCoefficients(); }; #endif // S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_JITTER_HPP_ From 9b9f5dea6bbb81fa8074e188a506a0bfd8cf176d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:39:13 +0100 Subject: [PATCH 0799/1086] Fix function argument names --- .../real/aocs/initialize_reaction_wheel.cpp | 20 +++++++++---------- src/components/real/aocs/reaction_wheel.cpp | 20 +++++++++---------- src/components/real/aocs/reaction_wheel.hpp | 20 +++++++++---------- .../real/aocs/reaction_wheel_jitter.cpp | 17 ++++++++-------- .../real/aocs/reaction_wheel_jitter.hpp | 15 +++++++------- 5 files changed, 47 insertions(+), 45 deletions(-) diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index cfd47a726..1c62e1b64 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -26,9 +26,9 @@ libra::Vector<3> ordinary_lag_coef(1.0); libra::Vector<3> coasting_lag_coef(1.0); bool is_calc_jitter_enabled; bool is_log_jitter_enabled; -std::vector> radial_force_harmonics_coef; -std::vector> radial_torque_harmonics_coef; -double structural_resonance_freq; +std::vector> radial_force_harmonics_coefficients; +std::vector> radial_torque_harmonics_coefficients; +double structural_resonance_frequency_Hz; double damping_factor; double bandwidth; bool considers_structural_resonance; @@ -80,10 +80,10 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double int harmonics_degree = rwmodel_conf.ReadInt(RWsection, "harmonics_degree"); IniAccess conf_radial_force_harmonics(radial_force_harmonics_coef_path); IniAccess conf_radial_torque_harmonics(radial_torque_harmonics_coef_path); - conf_radial_force_harmonics.ReadCsvDouble(radial_force_harmonics_coef, harmonics_degree); - conf_radial_torque_harmonics.ReadCsvDouble(radial_torque_harmonics_coef, harmonics_degree); + conf_radial_force_harmonics.ReadCsvDouble(radial_force_harmonics_coefficients, harmonics_degree); + conf_radial_torque_harmonics.ReadCsvDouble(radial_torque_harmonics_coefficients, harmonics_degree); - structural_resonance_freq = rwmodel_conf.ReadDouble(RWsection, "structural_resonance_frequency_Hz"); + structural_resonance_frequency_Hz = rwmodel_conf.ReadDouble(RWsection, "structural_resonance_frequency_Hz"); damping_factor = rwmodel_conf.ReadDouble(RWsection, "damping_factor"); bandwidth = rwmodel_conf.ReadDouble(RWsection, "bandwidth"); considers_structural_resonance = rwmodel_conf.ReadEnable(RWsection, "considers_structural_resonance"); @@ -103,8 +103,8 @@ RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::strin RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, - radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, bandwidth, - considers_structural_resonance, drive_flag, init_velocity); + radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, + bandwidth, considers_structural_resonance, drive_flag, init_velocity); return rwmodel; } @@ -117,8 +117,8 @@ RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, - is_log_jitter_enabled, radial_force_harmonics_coef, radial_torque_harmonics_coef, structural_resonance_freq, damping_factor, - bandwidth, considers_structural_resonance, drive_flag, init_velocity); + is_log_jitter_enabled, radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, + damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); return rwmodel; } diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index c5c485805..d8d507adc 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -21,9 +21,9 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, - double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, - double init_velocity) + vector> radial_force_harmonics_coefficients, vector> radial_torque_harmonics_coefficients, + double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, + bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, fast_prescaler), component_id_(component_id), inertia_(inertia), @@ -38,8 +38,8 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera drive_flag_(drive_flag), dt_main_routine_(dt_main_routine), ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), - rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, quaternion_b2c, structural_resonance_freq, - damping_factor, bandwidth, considers_structural_resonance), + rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, + structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { Initialize(); @@ -49,9 +49,9 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coef, vector> radial_torque_harmonics_coef, - double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, - double init_velocity) + vector> radial_force_harmonics_coefficients, vector> radial_torque_harmonics_coefficients, + double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, + bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, power_port, fast_prescaler), component_id_(component_id), inertia_(inertia), @@ -66,8 +66,8 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera drive_flag_(drive_flag), dt_main_routine_(dt_main_routine), ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), - rw_jitter_(radial_force_harmonics_coef, radial_torque_harmonics_coef, jitter_update_interval, quaternion_b2c, structural_resonance_freq, - damping_factor, bandwidth, considers_structural_resonance), + rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, + structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { Initialize(); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index e16318664..a452921bb 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -45,9 +45,9 @@ class RWModel : public Component, public ILoggable { * @param [in] coasting_lag_coef: Coasting lag coefficients * @param [in] is_calc_jitter_enabled: Enable flag to calculate RW jitter * @param [in] is_log_jitter_enabled: Enable flag to log output RW jitter - * @param [in] radial_force_harmonics_coef: Coefficients for radial force harmonics - * @param [in] radial_torque_harmonics_coef: Coefficients for radial torque harmonics - * @param [in] structural_resonance_freq: Frequency of structural resonance [Hz] + * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics + * @param [in] radial_torque_harmonics_coefficients: Coefficients for radial torque harmonics + * @param [in] structural_resonance_frequency_Hz: Frequency of structural resonance [Hz] * @param [in] damping_factor: Damping factor of structural resonance * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance @@ -58,8 +58,8 @@ class RWModel : public Component, public ILoggable { const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, + std::vector> radial_force_harmonics_coefficients, std::vector> radial_torque_harmonics_coefficients, + double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); /** * @fn RWModel @@ -82,9 +82,9 @@ class RWModel : public Component, public ILoggable { * @param [in] coasting_lag_coef: Coasting lag coefficients * @param [in] is_calc_jitter_enabled: Enable flag to calculate RW jitter * @param [in] is_log_jitter_enabled: Enable flag to log output RW jitter - * @param [in] radial_force_harmonics_coef: Coefficients for radial force harmonics - * @param [in] radial_torque_harmonics_coef: Coefficients for radial torque harmonics - * @param [in] structural_resonance_freq: Frequency of structural resonance [Hz] + * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics + * @param [in] radial_torque_harmonics_coefficients: Coefficients for radial torque harmonics + * @param [in] structural_resonance_frequency_Hz: Frequency of structural resonance [Hz] * @param [in] damping_factor: Damping factor of structural resonance * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance @@ -95,8 +95,8 @@ class RWModel : public Component, public ILoggable { const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - double structural_resonance_freq, double damping_factor, double bandwidth, bool considers_structural_resonance, + std::vector> radial_force_harmonics_coefficients, std::vector> radial_torque_harmonics_coefficients, + double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity = 0.0); // Override functions for Component diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 27251fe11..65f6b46df 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -8,15 +8,16 @@ #include #include -RWJitter::RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - const double jitter_update_interval, const libra::Quaternion quaternion_b2c, const double structural_resonance_freq, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance) - : radial_force_harmonics_coefficients_(radial_force_harmonics_coef), - radial_torque_harmonics_coefficients_(radial_torque_harmonics_coef), - update_interval_s_(jitter_update_interval), +RWJitter::RWJitter(std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, + const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, const double damping_factor, + const double bandwidth, const bool considers_structural_resonance) + : radial_force_harmonics_coefficients_(radial_force_harmonics_coefficients), + radial_torque_harmonics_coefficients_(radial_torque_harmonics_coefficients), + update_interval_s_(update_interval_s), quaternion_b2c_(quaternion_b2c), - structural_resonance_frequency_Hz_(structural_resonance_freq), - structural_resonance_angular_frequency_Hz_(libra::tau * structural_resonance_freq), + structural_resonance_frequency_Hz_(structural_resonance_frequency_Hz), + structural_resonance_angular_frequency_Hz_(libra::tau * structural_resonance_frequency_Hz), damping_factor_(damping_factor), bandwidth_(bandwidth), considers_structural_resonance_(considers_structural_resonance) { diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 39a800609..978ab51ac 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -20,18 +20,19 @@ class RWJitter { /** * @fn RWJitter * @brief Constructor - * @param [in] radial_force_harmonics_coef: Coefficients for radial force harmonics - * @param [in] radial_torque_harmonics_coef: Coefficients for radial torque harmonics - * @param [in] jitter_update_interval: Jitter update interval [sec] + * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics + * @param [in] radial_torque_harmonics_coefficients: Coefficients for radial torque harmonics + * @param [in] update_interval_s: Jitter update interval [sec] * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] structural_resonance_freq: Frequency of structural resonance [Hz] + * @param [in] structural_resonance_frequency_Hz: Frequency of structural resonance [Hz] * @param [in] damping_factor: Damping factor of structural resonance * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance */ - RWJitter(std::vector> radial_force_harmonics_coef, std::vector> radial_torque_harmonics_coef, - const double jitter_update_interval, const libra::Quaternion quaternion_b2c, const double structural_resonance_freq, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance); + RWJitter(std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, + const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, const double damping_factor, + const double bandwidth, const bool considers_structural_resonance); /** * @fn ~RWJitter * @brief Destructor From 0aa2c19f217a83c72700f511886f2900a89e375b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:40:36 +0100 Subject: [PATCH 0800/1086] Fix public function name --- src/components/real/aocs/reaction_wheel.cpp | 6 +++--- src/components/real/aocs/reaction_wheel.hpp | 4 ++-- .../real/aocs/reaction_wheel_jitter.hpp | 18 +++++++++--------- 3 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index d8d507adc..8b6c3e4f4 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -153,7 +153,7 @@ libra::Vector<3> RWModel::CalcTorque() { const libra::Vector<3> RWModel::GetOutputTorqueB() const { if (is_calculated_jitter_) { // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torqur_b - return output_torque_b_ - libra::OuterProduct(pos_b_, rw_jitter_.GetJitterForceB()) - rw_jitter_.GetJitterTorqueB(); + return output_torque_b_ - libra::OuterProduct(pos_b_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); } else { return output_torque_b_; } @@ -208,8 +208,8 @@ std::string RWModel::GetLogValue() const { str_tmp += WriteScalar(angular_acceleration_); if (is_logged_jitter_) { - str_tmp += WriteVector(rw_jitter_.GetJitterForceC()); - str_tmp += WriteVector(rw_jitter_.GetJitterTorqueC()); + str_tmp += WriteVector(rw_jitter_.GetJitterForce_c_N()); + str_tmp += WriteVector(rw_jitter_.GetJitterTorque_c_Nm()); } return str_tmp; diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index a452921bb..7c9280919 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -135,10 +135,10 @@ class RWModel : public Component, public ILoggable { */ const libra::Vector<3> GetOutputTorqueB() const; /** - * @fn GetJitterForceB + * @fn GetJitterForce_b_N * @brief Return output force by jitter in the body fixed frame [N] */ - const libra::Vector<3> GetJitterForceB() const { return rw_jitter_.GetJitterForceB(); } + const libra::Vector<3> GetJitterForce_b_N() const { return rw_jitter_.GetJitterForce_b_N(); } /** * @fn isMotorDrove * @brief Return drive flag diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 978ab51ac..9a3edaffb 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -47,27 +47,27 @@ class RWJitter { void CalcJitter(double angular_velocity_rad); /** - * @fn GetJitterForceB + * @fn GetJitterForce_b_N * @brief Return generated jitter force in the body fixed frame [N] */ - const libra::Vector<3> GetJitterForceB() const { return jitter_force_b_N_; } + const libra::Vector<3> GetJitterForce_b_N() const { return jitter_force_b_N_; } /** - * @fn GetJitterTorqueB + * @fn GetJitterTorque_b_Nm * @brief Return generated jitter torque in the body fixed frame [Nm] */ - const libra::Vector<3> GetJitterTorqueB() const { return jitter_torque_b_Nm_; } + const libra::Vector<3> GetJitterTorque_b_Nm() const { return jitter_torque_b_Nm_; } /** - * @fn GetJitterForceC + * @fn GetJitterForce_c_N * @brief Return generated jitter force in the components frame [N] */ - const libra::Vector<3> GetJitterForceC() const { + const libra::Vector<3> GetJitterForce_c_N() const { return considers_structural_resonance_ ? filtered_jitter_force_n_c_ : unfiltered_jitter_force_n_c_; } /** - * @fn GetJitterTorqueC + * @fn GetJitterTorque_c_Nm * @brief Return generated jitter torque in the component frame [Nm] */ - const libra::Vector<3> GetJitterTorqueC() const { + const libra::Vector<3> GetJitterTorque_c_Nm() const { return considers_structural_resonance_ ? filtered_jitter_torque_n_c_ : unfiltered_jitter_torque_n_c_; } @@ -88,7 +88,7 @@ class RWJitter { std::vector jitter_force_rotation_phase_; //!< 2 * pi * h_i * Omega * t [rad] std::vector jitter_torque_rotation_phase_; //!< 2 * pi * h_i * Omega * t [rad] - // Variables for solving difference equations in compo frame + // Variables for solving difference equations in component frame libra::Vector<3> unfiltered_jitter_force_n_c_{0.0}; libra::Vector<3> unfiltered_jitter_force_n_1_c_{0.0}; libra::Vector<3> unfiltered_jitter_force_n_2_c_{0.0}; From 2e9cb8ccae858c230b4a066ef8d41996ded5315b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:41:25 +0100 Subject: [PATCH 0801/1086] Rename RWJitter to ReactionWheelJitter --- src/components/real/aocs/reaction_wheel.hpp | 2 +- .../real/aocs/reaction_wheel_jitter.cpp | 18 +++++++++--------- .../real/aocs/reaction_wheel_jitter.hpp | 18 +++++++++--------- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 7c9280919..bee2e3e00 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -218,7 +218,7 @@ class RWModel : public Component, public ILoggable { libra::Vector<3> angular_momentum_b_{0.0}; //!< Angular momentum of RW [Nms] RwOde ode_angular_velocity_; //!< Reaction Wheel OrdinaryDifferentialEquation - RWJitter rw_jitter_; //!< RW jitter + ReactionWheelJitter rw_jitter_; //!< RW jitter bool is_calculated_jitter_ = false; //!< Flag for calculation of jitter bool is_logged_jitter_ = false; //!< Flag for log output of jitter diff --git a/src/components/real/aocs/reaction_wheel_jitter.cpp b/src/components/real/aocs/reaction_wheel_jitter.cpp index 65f6b46df..1099097ef 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.cpp +++ b/src/components/real/aocs/reaction_wheel_jitter.cpp @@ -8,10 +8,10 @@ #include #include -RWJitter::RWJitter(std::vector> radial_force_harmonics_coefficients, - std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, - const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, const double damping_factor, - const double bandwidth, const bool considers_structural_resonance) +ReactionWheelJitter::ReactionWheelJitter(std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, + const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance) : radial_force_harmonics_coefficients_(radial_force_harmonics_coefficients), radial_torque_harmonics_coefficients_(radial_torque_harmonics_coefficients), update_interval_s_(update_interval_s), @@ -38,9 +38,9 @@ RWJitter::RWJitter(std::vector> radial_force_harmonics_coeff } } -RWJitter::~RWJitter() {} +ReactionWheelJitter::~ReactionWheelJitter() {} -void RWJitter::CalcJitter(double angular_velocity_rad) { +void ReactionWheelJitter::CalcJitter(double angular_velocity_rad) { // Clear jitter in component frame unfiltered_jitter_force_n_c_ *= 0.0; unfiltered_jitter_torque_n_c_ *= 0.0; @@ -80,7 +80,7 @@ void RWJitter::CalcJitter(double angular_velocity_rad) { } } -void RWJitter::AddStructuralResonance() { +void ReactionWheelJitter::AddStructuralResonance() { // Solve difference equations for (int i = 0; i < 3; i++) { filtered_jitter_force_n_c_[i] = (-coefficients_[1] * filtered_jitter_force_n_1_c_[i] - coefficients_[2] * filtered_jitter_force_n_2_c_[i] + @@ -97,7 +97,7 @@ void RWJitter::AddStructuralResonance() { ShiftTimeStep(); } -void RWJitter::ShiftTimeStep() { +void ReactionWheelJitter::ShiftTimeStep() { unfiltered_jitter_force_n_2_c_ = unfiltered_jitter_force_n_1_c_; unfiltered_jitter_force_n_1_c_ = unfiltered_jitter_force_n_c_; filtered_jitter_force_n_2_c_ = filtered_jitter_force_n_1_c_; @@ -109,7 +109,7 @@ void RWJitter::ShiftTimeStep() { filtered_jitter_torque_n_1_c_ = filtered_jitter_torque_n_c_; } -void RWJitter::CalcCoefficients() { +void ReactionWheelJitter::CalcCoefficients() { // Pre-warping structural_resonance_angular_frequency_Hz_ = 2.0 / update_interval_s_ * tan(structural_resonance_angular_frequency_Hz_ * update_interval_s_ / 2.0); // Calculate coefficients of difference equation diff --git a/src/components/real/aocs/reaction_wheel_jitter.hpp b/src/components/real/aocs/reaction_wheel_jitter.hpp index 9a3edaffb..8e2607f49 100644 --- a/src/components/real/aocs/reaction_wheel_jitter.hpp +++ b/src/components/real/aocs/reaction_wheel_jitter.hpp @@ -12,13 +12,13 @@ #include /* - * @class RWJitter + * @class ReactionWheelJitter * @brief Class to calculate RW high-frequency jitter effect */ -class RWJitter { +class ReactionWheelJitter { public: /** - * @fn RWJitter + * @fn ReactionWheelJitter * @brief Constructor * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics * @param [in] radial_torque_harmonics_coefficients: Coefficients for radial torque harmonics @@ -29,15 +29,15 @@ class RWJitter { * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance */ - RWJitter(std::vector> radial_force_harmonics_coefficients, - std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, - const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, const double damping_factor, - const double bandwidth, const bool considers_structural_resonance); + ReactionWheelJitter(std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, const double update_interval_s, + const libra::Quaternion quaternion_b2c, const double structural_resonance_frequency_Hz, const double damping_factor, + const double bandwidth, const bool considers_structural_resonance); /** - * @fn ~RWJitter + * @fn ~ReactionWheelJitter * @brief Destructor */ - ~RWJitter(); + ~ReactionWheelJitter(); /** * @fn CalcJitter From 59d626f688433e3c0bfbe5158b2e465bc0e8d5fb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:43:01 +0100 Subject: [PATCH 0802/1086] Remove using --- src/components/real/aocs/reaction_wheel_ode.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 5b157048f..1deececcc 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -6,14 +6,12 @@ #include -using namespace libra; - -RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, Vector<3> lag_coef) +RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, libra::Vector<3> lag_coef) : OrdinaryDifferentialEquation<1>(step_width), lag_coef_(lag_coef), kInitAngularVelocity_(init_angular_velocity), target_angular_velocity_(target_angular_velocity) { - this->Setup(0.0, Vector<1>(init_angular_velocity)); + this->Setup(0.0, libra::Vector<1>(init_angular_velocity)); } double RwOde::getAngularVelocity(void) const { @@ -21,7 +19,7 @@ double RwOde::getAngularVelocity(void) const { return angular_velocity; } -void RwOde::DerivativeFunction(double x, const Vector<1> &state, Vector<1> &rhs) { +void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::Vector<1> &rhs) { // FIXME: fix this function UNUSED(x); UNUSED(state); @@ -46,4 +44,4 @@ void RwOde::DerivativeFunction(double x, const Vector<1> &state, Vector<1> &rhs) void RwOde::setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_ = angular_velocity; } -void RwOde::setLagCoef(const Vector<3> lag_coef) { lag_coef_ = lag_coef; } +void RwOde::setLagCoef(const libra::Vector<3> lag_coef) { lag_coef_ = lag_coef; } From bde030ad32fe4892ad9add580ce2cb9a090b253c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:47:19 +0100 Subject: [PATCH 0803/1086] Fix private function name --- .../real/aocs/reaction_wheel_ode.cpp | 23 ++++++++----------- .../real/aocs/reaction_wheel_ode.hpp | 7 +++--- 2 files changed, 13 insertions(+), 17 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index 1deececcc..c518bd4b7 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -7,10 +7,7 @@ #include RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, libra::Vector<3> lag_coef) - : OrdinaryDifferentialEquation<1>(step_width), - lag_coef_(lag_coef), - kInitAngularVelocity_(init_angular_velocity), - target_angular_velocity_(target_angular_velocity) { + : OrdinaryDifferentialEquation<1>(step_width), lag_coefficients_(lag_coef), target_angular_velocity_rad_s_(target_angular_velocity) { this->Setup(0.0, libra::Vector<1>(init_angular_velocity)); } @@ -30,18 +27,18 @@ void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::V // printf("zerodev %f\n", zero_deviation); // printf("onedev %f\n", one_deviation); - // rhs[0] =0.8*(target_angular_velocity_ - this->state()[0]) / + // rhs[0] =0.8*(target_angular_velocity_rad_s_ - this->state()[0]) / // (first_order_lag_)-second_order_coef_*this->state()[1]; rhs[0] = - // 0.00030016*(target_angular_velocity_ - this->state()[0]) + - // 0.9899*this->state()[1]-0.0245; rhs[0] = lag_coef_[2] * this->state()[1] + - // lag_coef_[1] * (target_angular_velocity_ - this->state()[0]) + - // lag_coef_[0]; + // 0.00030016*(target_angular_velocity_rad_s_ - this->state()[0]) + + // 0.9899*this->state()[1]-0.0245; rhs[0] = lag_coefficients_[2] * this->state()[1] + + // lag_coefficients_[1] * (target_angular_velocity_rad_s_ - this->state()[0]) + + // lag_coefficients_[0]; // First-order-lag - rhs[0] = (target_angular_velocity_ - this->GetState()[0]) / (lag_coef_[0]); + rhs[0] = (target_angular_velocity_rad_s_ - this->GetState()[0]) / (lag_coefficients_[0]); // Only target - // rhs[0] = (target_angular_velocity_); + // rhs[0] = (target_angular_velocity_rad_s_); } -void RwOde::setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_ = angular_velocity; } +void RwOde::setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } -void RwOde::setLagCoef(const libra::Vector<3> lag_coef) { lag_coef_ = lag_coef; } +void RwOde::setLagCoef(const libra::Vector<3> lag_coef) { lag_coefficients_ = lag_coef; } diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 776c5c755..7a3a9fba2 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -64,10 +64,9 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { void setLagCoef(libra::Vector<3> lag_coef); private: - RwOde(double step_width); //!< Prohibit calling constructor - libra::Vector<3> lag_coef_; //!< Coefficients for the first order lag - const double kInitAngularVelocity_; //!< Initial angular velocity [rad/s] - double target_angular_velocity_; //!< Target angular velocity [rad/s] + RwOde(double step_width); //!< Prohibit calling constructor + libra::Vector<3> lag_coefficients_; //!< Coefficients for the first order lag + double target_angular_velocity_rad_s_; //!< Target angular velocity [rad/s] }; #endif // S2E_COMPONENTS_REAL_AOCS_REACTION_WHEEL_ODE_HPP_ From 6e2d7afe67cd36c575c5d4310bcc468e4ce98691 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:49:13 +0100 Subject: [PATCH 0804/1086] Fix function argument names --- .../real/aocs/initialize_reaction_wheel.cpp | 8 ++++---- src/components/real/aocs/reaction_wheel.cpp | 14 +++++++------- src/components/real/aocs/reaction_wheel.hpp | 8 ++++---- src/components/real/aocs/reaction_wheel_ode.cpp | 9 +++++---- src/components/real/aocs/reaction_wheel_ode.hpp | 13 +++++++------ .../math/ordinary_differential_equation.hpp | 8 ++++---- ...ry_differential_equation_template_functions.hpp | 4 ++-- 7 files changed, 33 insertions(+), 31 deletions(-) diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index 1c62e1b64..b10937b53 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -13,7 +13,7 @@ namespace { int prescaler; int fast_prescaler; -double step_width; +double step_width_s; double dt_main_routine; double jitter_update_interval; double inertia; @@ -92,7 +92,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double init_velocity = rwmodel_conf.ReadDouble(RWsection, "initial_angular_velocity_rad_s"); // Calc periods - step_width = prop_step; + step_width_s = prop_step; dt_main_routine = prescaler * compo_update_step; jitter_update_interval = fast_prescaler * compo_update_step; } @@ -101,7 +101,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, max_torque, + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); @@ -115,7 +115,7 @@ RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width, dt_main_routine, jitter_update_interval, inertia, + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width_s, dt_main_routine, jitter_update_interval, inertia, max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 8b6c3e4f4..44a2353bb 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -17,7 +17,7 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int component_id, double step_width, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int component_id, double step_width_s, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -31,7 +31,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), pos_b_(pos_b), - step_width_(step_width), + step_width_(step_width_s), dead_time_(dead_time), driving_lag_coef_(driving_lag_coef), coasting_lag_coef_(coasting_lag_coef), @@ -45,10 +45,10 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, double step_width, - double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, - libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, - libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, +RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, + double step_width_s, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, + double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, + libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, vector> radial_force_harmonics_coefficients, vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity) @@ -59,7 +59,7 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), pos_b_(pos_b), - step_width_(step_width), + step_width_(step_width_s), dead_time_(dead_time), driving_lag_coef_(driving_lag_coef), coasting_lag_coef_(coasting_lag_coef), diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index bee2e3e00..9c6a073bb 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -32,7 +32,7 @@ class RWModel : public Component, public ILoggable { * @param [in] fast_prescaler: Frequency scale factor for fast update * @param [in] clock_generator: Clock generator * @param [in] component_id: Component ID - * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] + * @param [in] step_width_s: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] * @param [in] inertia: Moment of inertia of the RW [kgm2] @@ -54,7 +54,7 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width, + RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, @@ -69,7 +69,7 @@ class RWModel : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] component_id: Component ID - * @param [in] step_width: Step width of integration by reaction wheel ordinary differential equation [sec] + * @param [in] step_width_s: Step width of integration by reaction wheel ordinary differential equation [sec] * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] * @param [in] jitter_update_interval: Update period of RW jitter [sec] * @param [in] inertia: Moment of inertia of the RW [kgm2] @@ -92,7 +92,7 @@ class RWModel : public Component, public ILoggable { * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - const double step_width, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, + const double step_width_s, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coefficients, std::vector> radial_torque_harmonics_coefficients, diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index c518bd4b7..f023794ac 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -6,9 +6,10 @@ #include -RwOde::RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, libra::Vector<3> lag_coef) - : OrdinaryDifferentialEquation<1>(step_width), lag_coefficients_(lag_coef), target_angular_velocity_rad_s_(target_angular_velocity) { - this->Setup(0.0, libra::Vector<1>(init_angular_velocity)); +RwOde::RwOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, + const libra::Vector<3> lag_coefficients) + : OrdinaryDifferentialEquation<1>(step_width_s), lag_coefficients_(lag_coefficients), target_angular_velocity_rad_s_(target_angular_velocity) { + this->Setup(0.0, libra::Vector<1>(initial_angular_velocity)); } double RwOde::getAngularVelocity(void) const { @@ -41,4 +42,4 @@ void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::V void RwOde::setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } -void RwOde::setLagCoef(const libra::Vector<3> lag_coef) { lag_coefficients_ = lag_coef; } +void RwOde::setLagCoef(const libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 7a3a9fba2..1906daefc 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -19,12 +19,13 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { /** * @fn RwOde * @brief Constructor - * @param [in] step_width: Step width for OrdinaryDifferentialEquation calculation - * @param [in] init_angular_velocity: Initial angular velocity [rad/s] + * @param [in] step_width_s: Step width for OrdinaryDifferentialEquation calculation + * @param [in] initial_angular_velocity: Initial angular velocity [rad/s] * @param [in] target_angular_velocity: Target angular velocity [rad/s] - * @param [in] lag_coef: coefficients for first order lag + * @param [in] lag_coefficients: coefficients for first order lag */ - RwOde(double step_width, double init_angular_velocity, double target_angular_velocity, libra::Vector<3> lag_coef); + RwOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, + const libra::Vector<3> lag_coefficients); /** * @fn DerivativeFunction @@ -61,10 +62,10 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { * @fn setLagCoef * @brief Set lag coefficients */ - void setLagCoef(libra::Vector<3> lag_coef); + void setLagCoef(libra::Vector<3> lag_coefficients); private: - RwOde(double step_width); //!< Prohibit calling constructor + RwOde(double step_width_s); //!< Prohibit calling constructor libra::Vector<3> lag_coefficients_; //!< Coefficients for the first order lag double target_angular_velocity_rad_s_; //!< Target angular velocity [rad/s] }; diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index 4072ae778..c50e369ae 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -20,9 +20,9 @@ class OrdinaryDifferentialEquation { /** * @fn OrdinaryDifferentialEquation * @brief Constructor - * @param [in] step_width: Step width + * @param [in] step_width_s: Step width */ - OrdinaryDifferentialEquation(double step_width); + OrdinaryDifferentialEquation(double step_width_s); /** * @fn ~OrdinaryDifferentialEquation * @brief Destructor @@ -61,9 +61,9 @@ class OrdinaryDifferentialEquation { /** * @fn SetStepWidth * @brief Initialize the state vector - * @param [in] step_width: Step width + * @param [in] step_width_s: Step width */ - inline void SetStepWidth(const double step_width) { step_width_ = step_width; } + inline void SetStepWidth(const double step_width_s) { step_width_ = step_width_s; } // Getter /** diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 7bef1b5f5..0ccabca9f 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -8,8 +8,8 @@ namespace libra { template -OrdinaryDifferentialEquation::OrdinaryDifferentialEquation(double step_width) - : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width) {} +OrdinaryDifferentialEquation::OrdinaryDifferentialEquation(double step_width_s) + : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width_s) {} template void OrdinaryDifferentialEquation::Setup(double initial_independent_variable, const Vector& initial_state) { From 8400dc569ddf8f5979758b8e50ecc9b4aced4f33 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:51:33 +0100 Subject: [PATCH 0805/1086] Move inline functions --- src/components/real/aocs/reaction_wheel_ode.cpp | 9 --------- src/components/real/aocs/reaction_wheel_ode.hpp | 15 ++++++++------- 2 files changed, 8 insertions(+), 16 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index f023794ac..cbb18fd02 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -12,11 +12,6 @@ RwOde::RwOde(const double step_width_s, const double initial_angular_velocity, c this->Setup(0.0, libra::Vector<1>(initial_angular_velocity)); } -double RwOde::getAngularVelocity(void) const { - double angular_velocity = this->GetState()[0]; - return angular_velocity; -} - void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::Vector<1> &rhs) { // FIXME: fix this function UNUSED(x); @@ -39,7 +34,3 @@ void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::V // Only target // rhs[0] = (target_angular_velocity_rad_s_); } - -void RwOde::setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } - -void RwOde::setLagCoef(const libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 1906daefc..494b74775 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -40,13 +40,19 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { * @fn getAngularVelocity * @brief Return current angular velocity of RW rotor [rad/s] */ - double getAngularVelocity(void) const; + double getAngularVelocity(void) const { return this->GetState()[0]; } /** * @fn setTargetAngularVelocity * @brief Set target angular velocity [rad/s] */ - void setTargetAngularVelocity(double angular_velocity); + void setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } + + /** + * @fn setLagCoef + * @brief Set lag coefficients + */ + void setLagCoef(libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } /** * @fn setFirstOrderLag @@ -58,11 +64,6 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { * @brief Set second order lag coefficient (Currently not used) */ void setSecondOrderCoef(double second_order_coef); - /** - * @fn setLagCoef - * @brief Set lag coefficients - */ - void setLagCoef(libra::Vector<3> lag_coefficients); private: RwOde(double step_width_s); //!< Prohibit calling constructor From 0e162989d556a2f67045daf591806b30b61ac5fb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:51:56 +0100 Subject: [PATCH 0806/1086] Delete unused public functions --- src/components/real/aocs/reaction_wheel_ode.hpp | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 494b74775..96f7db284 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -54,17 +54,6 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { */ void setLagCoef(libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } - /** - * @fn setFirstOrderLag - * @brief Set first order lag coefficient (Currently not used) - */ - void setFirstOrderLag(double first_order_lag); - /** - * @fn setSecondOrderCoef - * @brief Set second order lag coefficient (Currently not used) - */ - void setSecondOrderCoef(double second_order_coef); - private: RwOde(double step_width_s); //!< Prohibit calling constructor libra::Vector<3> lag_coefficients_; //!< Coefficients for the first order lag From 6e02fc93dc08725091f935daff93ddff279895e9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:53:18 +0100 Subject: [PATCH 0807/1086] Fix public function name --- src/components/real/aocs/reaction_wheel.cpp | 10 +++++----- src/components/real/aocs/reaction_wheel_ode.hpp | 12 ++++++------ 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 44a2353bb..7f3d04fe7 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -111,15 +111,15 @@ libra::Vector<3> RWModel::CalcTorque() { if (!drive_flag_) // RW power off -> coasting mode { // Set lag coefficient - ode_angular_velocity_.setLagCoef(coasting_lag_coef_); + ode_angular_velocity_.SetLagCoefficients(coasting_lag_coef_); // Set target velocity - ode_angular_velocity_.setTargetAngularVelocity(0.0); + ode_angular_velocity_.SetTargetAngularVelocity_rad_s(0.0); // Clear delay buffer std::fill(delay_buffer_accl_.begin(), delay_buffer_accl_.end(), 0.0); } else // RW power on { // Set lag coefficient - ode_angular_velocity_.setLagCoef(driving_lag_coef_); + ode_angular_velocity_.SetLagCoefficients(driving_lag_coef_); // Set target velocity from target torque double angular_accl = delay_buffer_accl_.front(); double target_angular_velocity_rad = pre_angular_velocity_rad + angular_accl; @@ -130,7 +130,7 @@ libra::Vector<3> RWModel::CalcTorque() { else if (target_angular_velocity_rad < -1.0 * velocity_limit_rad) target_angular_velocity_rad = -1.0 * velocity_limit_rad; // Set target velocity - ode_angular_velocity_.setTargetAngularVelocity(target_angular_velocity_rad); + ode_angular_velocity_.SetTargetAngularVelocity_rad_s(target_angular_velocity_rad); // Update delay buffer delay_buffer_accl_.push_back(target_accl_); delay_buffer_accl_.erase(delay_buffer_accl_.begin()); @@ -141,7 +141,7 @@ libra::Vector<3> RWModel::CalcTorque() { ++ode_angular_velocity_; // propagate() } // Substitution - angular_velocity_rad_ = ode_angular_velocity_.getAngularVelocity(); + angular_velocity_rad_ = ode_angular_velocity_.GetAngularVelocity_rad_s(); angular_velocity_rpm_ = angularVelocity2rpm(angular_velocity_rad_); angular_acceleration_ = (angular_velocity_rad_ - pre_angular_velocity_rad) / dt_main_routine_; // Component frame -> Body frame diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index 96f7db284..dadfa65f5 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -37,22 +37,22 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { void DerivativeFunction(double x, const libra::Vector<1>& state, libra::Vector<1>& rhs) override; /** - * @fn getAngularVelocity + * @fn GetAngularVelocity_rad_s * @brief Return current angular velocity of RW rotor [rad/s] */ - double getAngularVelocity(void) const { return this->GetState()[0]; } + double GetAngularVelocity_rad_s(void) const { return this->GetState()[0]; } /** - * @fn setTargetAngularVelocity + * @fn SetTargetAngularVelocity_rad_s * @brief Set target angular velocity [rad/s] */ - void setTargetAngularVelocity(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } + void SetTargetAngularVelocity_rad_s(double angular_velocity) { target_angular_velocity_rad_s_ = angular_velocity; } /** - * @fn setLagCoef + * @fn SetLagCoefficients * @brief Set lag coefficients */ - void setLagCoef(libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } + void SetLagCoefficients(libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } private: RwOde(double step_width_s); //!< Prohibit calling constructor From 27613246fa0169aa410163db733ec1368a7eaae6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:53:58 +0100 Subject: [PATCH 0808/1086] Rename RwOde to ReactionWheelOde --- src/components/real/aocs/reaction_wheel.hpp | 10 +++++----- src/components/real/aocs/reaction_wheel_ode.cpp | 6 +++--- src/components/real/aocs/reaction_wheel_ode.hpp | 12 ++++++------ 3 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 9c6a073bb..a7bb79432 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -194,7 +194,7 @@ class RWModel : public Component, public ILoggable { libra::Vector<3> direction_b_; //!< Wheel rotation vector in the body fixed frame. // Fixed Parameters for control delay - const double step_width_; //!< step width for RwOde [sec] + const double step_width_; //!< step width for ReactionWheelOde [sec] const double dead_time_; //!< dead time [sec] const libra::Vector<3> driving_lag_coef_; //!< delay coefficient for normal drive const libra::Vector<3> coasting_lag_coef_; //!< delay coefficient for coasting drive(Power off) @@ -217,10 +217,10 @@ class RWModel : public Component, public ILoggable { libra::Vector<3> output_torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] libra::Vector<3> angular_momentum_b_{0.0}; //!< Angular momentum of RW [Nms] - RwOde ode_angular_velocity_; //!< Reaction Wheel OrdinaryDifferentialEquation - ReactionWheelJitter rw_jitter_; //!< RW jitter - bool is_calculated_jitter_ = false; //!< Flag for calculation of jitter - bool is_logged_jitter_ = false; //!< Flag for log output of jitter + ReactionWheelOde ode_angular_velocity_; //!< Reaction Wheel OrdinaryDifferentialEquation + ReactionWheelJitter rw_jitter_; //!< RW jitter + bool is_calculated_jitter_ = false; //!< Flag for calculation of jitter + bool is_logged_jitter_ = false; //!< Flag for log output of jitter // Local functions /** diff --git a/src/components/real/aocs/reaction_wheel_ode.cpp b/src/components/real/aocs/reaction_wheel_ode.cpp index cbb18fd02..71040254c 100644 --- a/src/components/real/aocs/reaction_wheel_ode.cpp +++ b/src/components/real/aocs/reaction_wheel_ode.cpp @@ -6,13 +6,13 @@ #include -RwOde::RwOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, - const libra::Vector<3> lag_coefficients) +ReactionWheelOde::ReactionWheelOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, + const libra::Vector<3> lag_coefficients) : OrdinaryDifferentialEquation<1>(step_width_s), lag_coefficients_(lag_coefficients), target_angular_velocity_rad_s_(target_angular_velocity) { this->Setup(0.0, libra::Vector<1>(initial_angular_velocity)); } -void RwOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::Vector<1> &rhs) { +void ReactionWheelOde::DerivativeFunction(double x, const libra::Vector<1> &state, libra::Vector<1> &rhs) { // FIXME: fix this function UNUSED(x); UNUSED(state); diff --git a/src/components/real/aocs/reaction_wheel_ode.hpp b/src/components/real/aocs/reaction_wheel_ode.hpp index dadfa65f5..5d726906d 100644 --- a/src/components/real/aocs/reaction_wheel_ode.hpp +++ b/src/components/real/aocs/reaction_wheel_ode.hpp @@ -11,21 +11,21 @@ #include /* - * @file RwOde + * @file ReactionWheelOde * @brief Ordinary differential equation of angular velocity of reaction wheel with first-order lag */ -class RwOde : public libra::OrdinaryDifferentialEquation<1> { +class ReactionWheelOde : public libra::OrdinaryDifferentialEquation<1> { public: /** - * @fn RwOde + * @fn ReactionWheelOde * @brief Constructor * @param [in] step_width_s: Step width for OrdinaryDifferentialEquation calculation * @param [in] initial_angular_velocity: Initial angular velocity [rad/s] * @param [in] target_angular_velocity: Target angular velocity [rad/s] * @param [in] lag_coefficients: coefficients for first order lag */ - RwOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, - const libra::Vector<3> lag_coefficients); + ReactionWheelOde(const double step_width_s, const double initial_angular_velocity, const double target_angular_velocity, + const libra::Vector<3> lag_coefficients); /** * @fn DerivativeFunction @@ -55,7 +55,7 @@ class RwOde : public libra::OrdinaryDifferentialEquation<1> { void SetLagCoefficients(libra::Vector<3> lag_coefficients) { lag_coefficients_ = lag_coefficients; } private: - RwOde(double step_width_s); //!< Prohibit calling constructor + ReactionWheelOde(double step_width_s); //!< Prohibit calling constructor libra::Vector<3> lag_coefficients_; //!< Coefficients for the first order lag double target_angular_velocity_rad_s_; //!< Target angular velocity [rad/s] }; From 431f40ca36481ab86bb750e4987b5c14d2a68d5d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 09:59:58 +0100 Subject: [PATCH 0809/1086] Fix private variable names --- src/components/real/aocs/reaction_wheel.cpp | 100 +++++++++--------- src/components/real/aocs/reaction_wheel.hpp | 48 ++++----- .../math/ordinary_differential_equation.hpp | 6 +- ...fferential_equation_template_functions.hpp | 18 ++-- 4 files changed, 86 insertions(+), 86 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 7f3d04fe7..374ee2f78 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -26,18 +26,18 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, fast_prescaler), component_id_(component_id), - inertia_(inertia), - max_torque_(max_torque), + rotor_inertia_kgm2_(inertia), + max_torque_Nm_(max_torque), max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), - pos_b_(pos_b), - step_width_(step_width_s), - dead_time_(dead_time), - driving_lag_coef_(driving_lag_coef), - coasting_lag_coef_(coasting_lag_coef), + position_b_m_(pos_b), + step_width_s_(step_width_s), + dead_time_s_(dead_time), + driving_lag_coefficients_(driving_lag_coef), + coasting_lag_coefficients_(coasting_lag_coef), drive_flag_(drive_flag), - dt_main_routine_(dt_main_routine), - ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), + main_routine_time_steo_s_(dt_main_routine), + ode_angular_velocity_(step_width_s_, init_velocity, 0.0, coasting_lag_coefficients_), rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), @@ -54,18 +54,18 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera bool drive_flag, double init_velocity) : Component(prescaler, clock_generator, power_port, fast_prescaler), component_id_(component_id), - inertia_(inertia), - max_torque_(max_torque), + rotor_inertia_kgm2_(inertia), + max_torque_Nm_(max_torque), max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), - pos_b_(pos_b), - step_width_(step_width_s), - dead_time_(dead_time), - driving_lag_coef_(driving_lag_coef), - coasting_lag_coef_(coasting_lag_coef), + position_b_m_(pos_b), + step_width_s_(step_width_s), + dead_time_s_(dead_time), + driving_lag_coefficients_(driving_lag_coef), + coasting_lag_coefficients_(coasting_lag_coef), drive_flag_(drive_flag), - dt_main_routine_(dt_main_routine), - ode_angular_velocity_(step_width_, init_velocity, 0.0, coasting_lag_coef_), + main_routine_time_steo_s_(dt_main_routine), + ode_angular_velocity_(step_width_s_, init_velocity, 0.0, coasting_lag_coefficients_), rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), @@ -74,20 +74,20 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera } void RWModel::Initialize() { - direction_c_ = libra::Vector<3>(0.0); - direction_c_[2] = 1.0; - direction_b_ = quaternion_b2c_.InverseFrameConversion(direction_c_); + rotation_axis_c_ = libra::Vector<3>(0.0); + rotation_axis_c_[2] = 1.0; + rotation_axis_b_ = quaternion_b2c_.InverseFrameConversion(rotation_axis_c_); velocity_limit_rpm_ = max_velocity_rpm_; - output_torque_b_ = libra::Vector<3>(0.0); - angular_momentum_b_ = libra::Vector<3>(0.0); - target_accl_ = 0.0; - int len_buffer = (int)floor(dead_time_ / dt_main_routine_) + 1; - delay_buffer_accl_.assign(len_buffer, 0.0); + output_torque_b_Nm_ = libra::Vector<3>(0.0); + angular_momentum_b_Nms_ = libra::Vector<3>(0.0); + target_acceleration_rad_s2_ = 0.0; + int len_buffer = (int)floor(dead_time_s_ / main_routine_time_steo_s_) + 1; + acceleration_delay_buffer_.assign(len_buffer, 0.0); - angular_acceleration_ = 0.0; + angular_acceleration_rad_s2_ = 0.0; angular_velocity_rpm_ = 0.0; - angular_velocity_rad_ = 0.0; + angular_velocity_rad_s_ = 0.0; // Turn on RW jitter calculation if (is_calculated_jitter_) { @@ -104,24 +104,24 @@ void RWModel::MainRoutine(int count) { void RWModel::PowerOffRoutine() { drive_flag_ = 0; } // Jitter calculation -void RWModel::FastUpdate() { rw_jitter_.CalcJitter(angular_velocity_rad_); } +void RWModel::FastUpdate() { rw_jitter_.CalcJitter(angular_velocity_rad_s_); } libra::Vector<3> RWModel::CalcTorque() { - double pre_angular_velocity_rad = angular_velocity_rad_; + double pre_angular_velocity_rad = angular_velocity_rad_s_; if (!drive_flag_) // RW power off -> coasting mode { // Set lag coefficient - ode_angular_velocity_.SetLagCoefficients(coasting_lag_coef_); + ode_angular_velocity_.SetLagCoefficients(coasting_lag_coefficients_); // Set target velocity ode_angular_velocity_.SetTargetAngularVelocity_rad_s(0.0); // Clear delay buffer - std::fill(delay_buffer_accl_.begin(), delay_buffer_accl_.end(), 0.0); + std::fill(acceleration_delay_buffer_.begin(), acceleration_delay_buffer_.end(), 0.0); } else // RW power on { // Set lag coefficient - ode_angular_velocity_.SetLagCoefficients(driving_lag_coef_); + ode_angular_velocity_.SetLagCoefficients(driving_lag_coefficients_); // Set target velocity from target torque - double angular_accl = delay_buffer_accl_.front(); + double angular_accl = acceleration_delay_buffer_.front(); double target_angular_velocity_rad = pre_angular_velocity_rad + angular_accl; // Check velocity limit double velocity_limit_rad = rpm2angularVelocity(velocity_limit_rpm_); @@ -132,30 +132,30 @@ libra::Vector<3> RWModel::CalcTorque() { // Set target velocity ode_angular_velocity_.SetTargetAngularVelocity_rad_s(target_angular_velocity_rad); // Update delay buffer - delay_buffer_accl_.push_back(target_accl_); - delay_buffer_accl_.erase(delay_buffer_accl_.begin()); + acceleration_delay_buffer_.push_back(target_acceleration_rad_s2_); + acceleration_delay_buffer_.erase(acceleration_delay_buffer_.begin()); } // Calc RW OrdinaryDifferentialEquation - int itr_num = (int)ceil(dt_main_routine_ / step_width_); + int itr_num = (int)ceil(main_routine_time_steo_s_ / step_width_s_); for (int i = 0; i < itr_num; i++) { ++ode_angular_velocity_; // propagate() } // Substitution - angular_velocity_rad_ = ode_angular_velocity_.GetAngularVelocity_rad_s(); - angular_velocity_rpm_ = angularVelocity2rpm(angular_velocity_rad_); - angular_acceleration_ = (angular_velocity_rad_ - pre_angular_velocity_rad) / dt_main_routine_; + angular_velocity_rad_s_ = ode_angular_velocity_.GetAngularVelocity_rad_s(); + angular_velocity_rpm_ = angularVelocity2rpm(angular_velocity_rad_s_); + angular_acceleration_rad_s2_ = (angular_velocity_rad_s_ - pre_angular_velocity_rad) / main_routine_time_steo_s_; // Component frame -> Body frame - output_torque_b_ = -1.0 * inertia_ * angular_acceleration_ * direction_b_; - angular_momentum_b_ = inertia_ * angular_velocity_rad_ * direction_b_; - return output_torque_b_; + output_torque_b_Nm_ = -1.0 * rotor_inertia_kgm2_ * angular_acceleration_rad_s2_ * rotation_axis_b_; + angular_momentum_b_Nms_ = rotor_inertia_kgm2_ * angular_velocity_rad_s_ * rotation_axis_b_; + return output_torque_b_Nm_; } const libra::Vector<3> RWModel::GetOutputTorqueB() const { if (is_calculated_jitter_) { // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torqur_b - return output_torque_b_ - libra::OuterProduct(pos_b_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); + return output_torque_b_Nm_ - libra::OuterProduct(position_b_m_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); } else { - return output_torque_b_; + return output_torque_b_Nm_; } } @@ -163,10 +163,10 @@ void RWModel::SetTargetTorqueRw(double torque_rw) { // Check Torque Limit double sign; torque_rw > 0 ? sign = 1.0 : sign = -1.0; - if (abs(torque_rw) < max_torque_) { - target_accl_ = torque_rw / inertia_; + if (abs(torque_rw) < max_torque_Nm_) { + target_acceleration_rad_s2_ = torque_rw / rotor_inertia_kgm2_; } else { - target_accl_ = sign * max_torque_ / inertia_; + target_acceleration_rad_s2_ = sign * max_torque_Nm_ / rotor_inertia_kgm2_; } } void RWModel::SetTargetTorqueBody(double torque_body) { SetTargetTorqueRw(-1.0 * torque_body); } @@ -202,10 +202,10 @@ std::string RWModel::GetLogHeader() const { std::string RWModel::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(angular_velocity_rad_); + str_tmp += WriteScalar(angular_velocity_rad_s_); str_tmp += WriteScalar(angular_velocity_rpm_); str_tmp += WriteScalar(velocity_limit_rpm_); - str_tmp += WriteScalar(angular_acceleration_); + str_tmp += WriteScalar(angular_acceleration_rad_s2_); if (is_logged_jitter_) { str_tmp += WriteVector(rw_jitter_.GetJitterForce_c_N()); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index a7bb79432..5cc6c069f 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -148,7 +148,7 @@ class RWModel : public Component, public ILoggable { * @fn GetVelocityRad * @brief Return angular velocity of RW rotor [rad/s] */ - inline double GetVelocityRad() const { return angular_velocity_rad_; }; + inline double GetVelocityRad() const { return angular_velocity_rad_s_; }; /** * @fn GetVelocityRpm * @brief Return angular velocity of RW rotor [RPM] @@ -158,7 +158,7 @@ class RWModel : public Component, public ILoggable { * @fn GetAngMomB * @brief Return angular momentum of RW [Nms] */ - inline const libra::Vector<3> GetAngMomB() const { return angular_momentum_b_; }; + inline const libra::Vector<3> GetAngMomB() const { return angular_momentum_b_Nms_; }; // Setter /** @@ -184,38 +184,38 @@ class RWModel : public Component, public ILoggable { protected: // Fixed Parameters - const int component_id_; //!< Actuator ID - const double inertia_; //!< Inertia of RW rotor [kgm2] - const double max_torque_; //!< Maximum output torque [Nm] - const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] - libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame - const libra::Vector<3> pos_b_; //!< Position of RW in the body fixed frame [m] - libra::Vector<3> direction_c_; //!< Wheel rotation axis on the component frame. Constant as (0 0 1). (Output torque is minus direction) - libra::Vector<3> direction_b_; //!< Wheel rotation vector in the body fixed frame. + const int component_id_; //!< Actuator ID + const double rotor_inertia_kgm2_; //!< Inertia of RW rotor [kgm2] + const double max_torque_Nm_; //!< Maximum output torque [Nm] + const double max_velocity_rpm_; //!< Maximum angular velocity of rotor [rpm] + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame + const libra::Vector<3> position_b_m_; //!< Position of RW in the body fixed frame [m] + libra::Vector<3> rotation_axis_c_; //!< Wheel rotation axis on the component frame. Constant as (0 0 1). (Output torque is minus direction) + libra::Vector<3> rotation_axis_b_; //!< Wheel rotation vector in the body fixed frame. // Fixed Parameters for control delay - const double step_width_; //!< step width for ReactionWheelOde [sec] - const double dead_time_; //!< dead time [sec] - const libra::Vector<3> driving_lag_coef_; //!< delay coefficient for normal drive - const libra::Vector<3> coasting_lag_coef_; //!< delay coefficient for coasting drive(Power off) + const double step_width_s_; //!< step width for ReactionWheelOde [sec] + const double dead_time_s_; //!< dead time [sec] + const libra::Vector<3> driving_lag_coefficients_; //!< delay coefficient for normal drive + const libra::Vector<3> coasting_lag_coefficients_; //!< delay coefficient for coasting drive(Power off) // Controlled Parameters - bool drive_flag_; //!< Drive flag(True: Drive, False: Stop) - double velocity_limit_rpm_; //!< Velocity limit defined by users [RPM] - double target_accl_; //!< Target acceleration [rad/s2] + bool drive_flag_; //!< Drive flag(True: Drive, False: Stop) + double velocity_limit_rpm_; //!< Velocity limit defined by users [RPM] + double target_acceleration_rad_s2_; //!< Target acceleration [rad/s2] // Internal variables for control delay - std::vector delay_buffer_accl_; //!< Delay buffer for acceleration - double dt_main_routine_; //!< Period of execution of main routine [sec] + std::vector acceleration_delay_buffer_; //!< Delay buffer for acceleration + double main_routine_time_steo_s_; //!< Period of execution of main routine [sec] // Output at RW frame - double angular_acceleration_ = 0.0; //!< Output angular acceleration [rad/s2] - double angular_velocity_rpm_ = 0.0; //!< Current angular velocity [rpm] - double angular_velocity_rad_ = 0.0; //!< Current angular velocity [rad/s] + double angular_acceleration_rad_s2_ = 0.0; //!< Output angular acceleration [rad/s2] + double angular_velocity_rpm_ = 0.0; //!< Current angular velocity [rpm] + double angular_velocity_rad_s_ = 0.0; //!< Current angular velocity [rad/s] // Output at body frame - libra::Vector<3> output_torque_b_{0.0}; //!< Output torque in the body fixed frame [Nm] - libra::Vector<3> angular_momentum_b_{0.0}; //!< Angular momentum of RW [Nms] + libra::Vector<3> output_torque_b_Nm_{0.0}; //!< Output torque in the body fixed frame [Nm] + libra::Vector<3> angular_momentum_b_Nms_{0.0}; //!< Angular momentum of RW [Nms] ReactionWheelOde ode_angular_velocity_; //!< Reaction Wheel OrdinaryDifferentialEquation ReactionWheelJitter rw_jitter_; //!< RW jitter diff --git a/src/library/math/ordinary_differential_equation.hpp b/src/library/math/ordinary_differential_equation.hpp index c50e369ae..dcb4c9d5f 100644 --- a/src/library/math/ordinary_differential_equation.hpp +++ b/src/library/math/ordinary_differential_equation.hpp @@ -63,14 +63,14 @@ class OrdinaryDifferentialEquation { * @brief Initialize the state vector * @param [in] step_width_s: Step width */ - inline void SetStepWidth(const double step_width_s) { step_width_ = step_width_s; } + inline void SetStepWidth(const double step_width_s) { step_width_s_ = step_width_s; } // Getter /** * @fn GetStepWidth * @brief Return step width */ - inline double GetStepWidth() const { return step_width_; } + inline double GetStepWidth() const { return step_width_s_; } /** * @fn GetIndependentVariable @@ -108,7 +108,7 @@ class OrdinaryDifferentialEquation { double independent_variable_; //!< Latest value of independent variable Vector state_; //!< Latest state vector Vector derivative_; //!< Latest differentiate of the state vector - double step_width_; //!< Step width + double step_width_s_; //!< Step width }; } // namespace libra diff --git a/src/library/math/ordinary_differential_equation_template_functions.hpp b/src/library/math/ordinary_differential_equation_template_functions.hpp index 0ccabca9f..4a06b54f2 100644 --- a/src/library/math/ordinary_differential_equation_template_functions.hpp +++ b/src/library/math/ordinary_differential_equation_template_functions.hpp @@ -9,7 +9,7 @@ namespace libra { template OrdinaryDifferentialEquation::OrdinaryDifferentialEquation(double step_width_s) - : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_(step_width_s) {} + : independent_variable_(0.0), state_(0.0), derivative_(0.0), step_width_s_(step_width_s) {} template void OrdinaryDifferentialEquation::Setup(double initial_independent_variable, const Vector& initial_state) { @@ -29,19 +29,19 @@ void OrdinaryDifferentialEquation::Update() { // 4th order Runge-Kutta method Vector k1(derivative_); - k1 *= step_width_; + k1 *= step_width_s_; Vector k2(state_.GetLength()); - DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k1, k2); - k2 *= step_width_; + DerivativeFunction(independent_variable_ + 0.5 * step_width_s_, state_ + 0.5 * k1, k2); + k2 *= step_width_s_; Vector k3(state_.GetLength()); - DerivativeFunction(independent_variable_ + 0.5 * step_width_, state_ + 0.5 * k2, k3); - k3 *= step_width_; + DerivativeFunction(independent_variable_ + 0.5 * step_width_s_, state_ + 0.5 * k2, k3); + k3 *= step_width_s_; Vector k4(state_.GetLength()); - DerivativeFunction(independent_variable_ + step_width_, state_ + k3, k4); - k4 *= step_width_; + DerivativeFunction(independent_variable_ + step_width_s_, state_ + k3, k4); + k4 *= step_width_s_; state_ += (1.0 / 6.0) * (k1 + 2.0 * (k2 + k3) + k4); // Update state vector - independent_variable_ += step_width_; // Update independent variable + independent_variable_ += step_width_s_; // Update independent variable } } // namespace libra From 3ffdb0db1bbe354e67c797bd65141ba0a45958a3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:09:44 +0100 Subject: [PATCH 0810/1086] Fix function arguments names --- .../real/aocs/initialize_reaction_wheel.cpp | 50 +++++++------- src/components/real/aocs/reaction_wheel.cpp | 68 +++++++++---------- src/components/real/aocs/reaction_wheel.hpp | 62 ++++++++--------- src/disturbances/gravity_gradient.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 4 +- src/dynamics/attitude/attitude_rk4.hpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/attitude/controlled_attitude.hpp | 2 +- 8 files changed, 97 insertions(+), 95 deletions(-) diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index b10937b53..67962cf1f 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -14,16 +14,16 @@ namespace { int prescaler; int fast_prescaler; double step_width_s; -double dt_main_routine; -double jitter_update_interval; -double inertia; -double max_torque; +double main_routine_time_step_s; +double jitter_update_interval_s; +double rotor_inertia_kgm2; +double max_torque_Nm; double max_velocity; libra::Quaternion quaternion_b2c; -libra::Vector<3> pos_b; -double dead_time; +libra::Vector<3> position_b_m; +double dead_time_s; libra::Vector<3> ordinary_lag_coef(1.0); -libra::Vector<3> coasting_lag_coef(1.0); +libra::Vector<3> coasting_lag_coefficients(1.0); bool is_calc_jitter_enabled; bool is_log_jitter_enabled; std::vector> radial_force_harmonics_coefficients; @@ -33,7 +33,7 @@ double damping_factor; double bandwidth; bool considers_structural_resonance; bool drive_flag; -double init_velocity; +double init_velocity_rad_s; void InitParams(int actuator_id, std::string file_name, double prop_step, double compo_update_step) { // Access Parameters @@ -49,8 +49,8 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double if (prescaler <= 1) prescaler = 1; fast_prescaler = rwmodel_conf.ReadInt(RWsection, "fast_prescaler"); if (fast_prescaler <= 1) fast_prescaler = 1; - inertia = rwmodel_conf.ReadDouble(RWsection, "moment_of_inertia_kgm2"); - max_torque = rwmodel_conf.ReadDouble(RWsection, "max_output_torque_Nm"); + rotor_inertia_kgm2 = rwmodel_conf.ReadDouble(RWsection, "moment_of_inertia_kgm2"); + max_torque_Nm = rwmodel_conf.ReadDouble(RWsection, "max_output_torque_Nm"); max_velocity = rwmodel_conf.ReadDouble(RWsection, "max_angular_velocity_rpm"); std::string direction_determination_mode; @@ -67,10 +67,10 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double quaternion_b2c = q.Conjugate(); } - rwmodel_conf.ReadVector(RWsection, "position_b_m", pos_b); - dead_time = rwmodel_conf.ReadDouble(RWsection, "dead_time_s"); + rwmodel_conf.ReadVector(RWsection, "position_b_m", position_b_m); + dead_time_s = rwmodel_conf.ReadDouble(RWsection, "dead_time_s"); // rwmodel_conf.ReadVector(RWsection, "first_order_lag_coefficient", ordinary_lag_coef); // TODO: Fix bug - // rwmodel_conf.ReadVector(RWsection, "coasting_lag_coefficient", coasting_lag_coef); // TODO: Fix bug + // rwmodel_conf.ReadVector(RWsection, "coasting_lag_coefficient", coasting_lag_coefficients); // TODO: Fix bug is_calc_jitter_enabled = rwmodel_conf.ReadEnable(RWsection, "jitter_calculation"); is_log_jitter_enabled = rwmodel_conf.ReadEnable(RWsection, "jitter_logging"); @@ -89,22 +89,23 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double considers_structural_resonance = rwmodel_conf.ReadEnable(RWsection, "considers_structural_resonance"); drive_flag = rwmodel_conf.ReadBoolean(RWsection, "initial_motor_drive_flag"); - init_velocity = rwmodel_conf.ReadDouble(RWsection, "initial_angular_velocity_rad_s"); + init_velocity_rad_s = rwmodel_conf.ReadDouble(RWsection, "initial_angular_velocity_rad_s"); // Calc periods step_width_s = prop_step; - dt_main_routine = prescaler * compo_update_step; - jitter_update_interval = fast_prescaler * compo_update_step; + main_routine_time_step_s = prescaler * compo_update_step; + jitter_update_interval_s = fast_prescaler * compo_update_step; } } // namespace RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, dt_main_routine, jitter_update_interval, inertia, max_torque, - max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, is_log_jitter_enabled, - radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, - bandwidth, considers_structural_resonance, drive_flag, init_velocity); + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, main_routine_time_step_s, jitter_update_interval_s, + rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, ordinary_lag_coef, + coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, + radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, + drive_flag, init_velocity_rad_s); return rwmodel; } @@ -115,10 +116,11 @@ RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width_s, dt_main_routine, jitter_update_interval, inertia, - max_torque, max_velocity, quaternion_b2c, pos_b, dead_time, ordinary_lag_coef, coasting_lag_coef, is_calc_jitter_enabled, - is_log_jitter_enabled, radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, - damping_factor, bandwidth, considers_structural_resonance, drive_flag, init_velocity); + RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width_s, main_routine_time_step_s, + jitter_update_interval_s, rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, + ordinary_lag_coef, coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, + radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, + drive_flag, init_velocity_rad_s); return rwmodel; } diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 374ee2f78..1bb50a4f3 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -18,27 +18,27 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int component_id, double step_width_s, - double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, double max_velocity_rpm, - libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, libra::Vector<3> driving_lag_coef, - libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coefficients, vector> radial_torque_harmonics_coefficients, - double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, - bool drive_flag, double init_velocity) + double main_routine_time_step_s, double jitter_update_interval_s, double rotor_inertia_kgm2, double max_torque_Nm, + double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> position_b_m, double dead_time_s, + libra::Vector<3> driving_lag_coefficients, libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, + bool is_log_jitter_enabled, vector> radial_force_harmonics_coefficients, + vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, + double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity_rad_s) : Component(prescaler, clock_generator, fast_prescaler), component_id_(component_id), - rotor_inertia_kgm2_(inertia), - max_torque_Nm_(max_torque), + rotor_inertia_kgm2_(rotor_inertia_kgm2), + max_torque_Nm_(max_torque_Nm), max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), - position_b_m_(pos_b), + position_b_m_(position_b_m), step_width_s_(step_width_s), - dead_time_s_(dead_time), - driving_lag_coefficients_(driving_lag_coef), - coasting_lag_coefficients_(coasting_lag_coef), + dead_time_s_(dead_time_s), + driving_lag_coefficients_(driving_lag_coefficients), + coasting_lag_coefficients_(coasting_lag_coefficients), drive_flag_(drive_flag), - main_routine_time_steo_s_(dt_main_routine), - ode_angular_velocity_(step_width_s_, init_velocity, 0.0, coasting_lag_coefficients_), - rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, + main_routine_time_step_s_(main_routine_time_step_s), + ode_angular_velocity_(step_width_s_, init_velocity_rad_s, 0.0, coasting_lag_coefficients_), + rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval_s, quaternion_b2c, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { @@ -46,27 +46,27 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera } RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - double step_width_s, double dt_main_routine, double jitter_update_interval, double inertia, double max_torque, - double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> pos_b, double dead_time, - libra::Vector<3> driving_lag_coef, libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - vector> radial_force_harmonics_coefficients, vector> radial_torque_harmonics_coefficients, - double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, - bool drive_flag, double init_velocity) + double step_width_s, double main_routine_time_step_s, double jitter_update_interval_s, double rotor_inertia_kgm2, + double max_torque_Nm, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> position_b_m, double dead_time_s, + libra::Vector<3> driving_lag_coefficients, libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, + bool is_log_jitter_enabled, vector> radial_force_harmonics_coefficients, + vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, + double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity_rad_s) : Component(prescaler, clock_generator, power_port, fast_prescaler), component_id_(component_id), - rotor_inertia_kgm2_(inertia), - max_torque_Nm_(max_torque), + rotor_inertia_kgm2_(rotor_inertia_kgm2), + max_torque_Nm_(max_torque_Nm), max_velocity_rpm_(max_velocity_rpm), quaternion_b2c_(quaternion_b2c), - position_b_m_(pos_b), + position_b_m_(position_b_m), step_width_s_(step_width_s), - dead_time_s_(dead_time), - driving_lag_coefficients_(driving_lag_coef), - coasting_lag_coefficients_(coasting_lag_coef), + dead_time_s_(dead_time_s), + driving_lag_coefficients_(driving_lag_coefficients), + coasting_lag_coefficients_(coasting_lag_coefficients), drive_flag_(drive_flag), - main_routine_time_steo_s_(dt_main_routine), - ode_angular_velocity_(step_width_s_, init_velocity, 0.0, coasting_lag_coefficients_), - rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval, quaternion_b2c, + main_routine_time_step_s_(main_routine_time_step_s), + ode_angular_velocity_(step_width_s_, init_velocity_rad_s, 0.0, coasting_lag_coefficients_), + rw_jitter_(radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, jitter_update_interval_s, quaternion_b2c, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance), is_calculated_jitter_(is_calc_jitter_enabled), is_logged_jitter_(is_log_jitter_enabled) { @@ -82,7 +82,7 @@ void RWModel::Initialize() { output_torque_b_Nm_ = libra::Vector<3>(0.0); angular_momentum_b_Nms_ = libra::Vector<3>(0.0); target_acceleration_rad_s2_ = 0.0; - int len_buffer = (int)floor(dead_time_s_ / main_routine_time_steo_s_) + 1; + int len_buffer = (int)floor(dead_time_s_ / main_routine_time_step_s_) + 1; acceleration_delay_buffer_.assign(len_buffer, 0.0); angular_acceleration_rad_s2_ = 0.0; @@ -136,14 +136,14 @@ libra::Vector<3> RWModel::CalcTorque() { acceleration_delay_buffer_.erase(acceleration_delay_buffer_.begin()); } // Calc RW OrdinaryDifferentialEquation - int itr_num = (int)ceil(main_routine_time_steo_s_ / step_width_s_); + int itr_num = (int)ceil(main_routine_time_step_s_ / step_width_s_); for (int i = 0; i < itr_num; i++) { ++ode_angular_velocity_; // propagate() } // Substitution angular_velocity_rad_s_ = ode_angular_velocity_.GetAngularVelocity_rad_s(); angular_velocity_rpm_ = angularVelocity2rpm(angular_velocity_rad_s_); - angular_acceleration_rad_s2_ = (angular_velocity_rad_s_ - pre_angular_velocity_rad) / main_routine_time_steo_s_; + angular_acceleration_rad_s2_ = (angular_velocity_rad_s_ - pre_angular_velocity_rad) / main_routine_time_step_s_; // Component frame -> Body frame output_torque_b_Nm_ = -1.0 * rotor_inertia_kgm2_ * angular_acceleration_rad_s2_ * rotation_axis_b_; angular_momentum_b_Nms_ = rotor_inertia_kgm2_ * angular_velocity_rad_s_ * rotation_axis_b_; @@ -152,7 +152,7 @@ libra::Vector<3> RWModel::CalcTorque() { const libra::Vector<3> RWModel::GetOutputTorqueB() const { if (is_calculated_jitter_) { - // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torqur_b + // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torque_b return output_torque_b_Nm_ - libra::OuterProduct(position_b_m_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); } else { return output_torque_b_Nm_; diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 5cc6c069f..0a56b483c 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -33,16 +33,16 @@ class RWModel : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] component_id: Component ID * @param [in] step_width_s: Step width of integration by reaction wheel ordinary differential equation [sec] - * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] - * @param [in] jitter_update_interval: Update period of RW jitter [sec] - * @param [in] inertia: Moment of inertia of the RW [kgm2] - * @param [in] max_torque: Maximum output torque [Nm] + * @param [in] main_routine_time_step_s: Period of execution of main routine of RW [sec] + * @param [in] jitter_update_interval_s: Update period of RW jitter [sec] + * @param [in] rotor_inertia_kgm2: Moment of rotor_inertia_kgm2 of the RW [kgm2] + * @param [in] max_torque_Nm: Maximum output torque [Nm] * @param [in] max_velocity_rpm: Maximum output angular velocity [RPM] * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] pos_b: Position of RW on the body fixed frame [m] - * @param [in] dead_time: Dead time of torque output [sec] - * @param [in] driving_lag_coef: Driving lag coefficients - * @param [in] coasting_lag_coef: Coasting lag coefficients + * @param [in] position_b_m: Position of RW on the body fixed frame [m] + * @param [in] dead_time_s: Dead time of torque output [sec] + * @param [in] driving_lag_coefficients: Driving lag coefficients + * @param [in] coasting_lag_coefficients: Coasting lag coefficients * @param [in] is_calc_jitter_enabled: Enable flag to calculate RW jitter * @param [in] is_log_jitter_enabled: Enable flag to log output RW jitter * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics @@ -52,15 +52,15 @@ class RWModel : public Component, public ILoggable { * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance * @param [in] drive_flag: RW drive flag - * @param [in] init_velocity: Initial value of angular velocity of RW + * @param [in] init_velocity_rad_s: Initial value of angular velocity of RW */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, - const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, - const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - std::vector> radial_force_harmonics_coefficients, std::vector> radial_torque_harmonics_coefficients, - double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, - const bool drive_flag = false, const double init_velocity = 0.0); + const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, const double max_torque_Nm, + const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, const double dead_time_s, + const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, + bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, + double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity_rad_s = 0.0); /** * @fn RWModel * @brief Constructor with power port @@ -70,16 +70,16 @@ class RWModel : public Component, public ILoggable { * @param [in] power_port: Power port * @param [in] component_id: Component ID * @param [in] step_width_s: Step width of integration by reaction wheel ordinary differential equation [sec] - * @param [in] dt_main_routine: Period of execution of main routine of RW [sec] - * @param [in] jitter_update_interval: Update period of RW jitter [sec] - * @param [in] inertia: Moment of inertia of the RW [kgm2] - * @param [in] max_torque: Maximum output torque [Nm] + * @param [in] main_routine_time_step_s: Period of execution of main routine of RW [sec] + * @param [in] jitter_update_interval_s: Update period of RW jitter [sec] + * @param [in] rotor_inertia_kgm2: Moment of rotor_inertia_kgm2 of the RW [kgm2] + * @param [in] max_torque_Nm: Maximum output torque [Nm] * @param [in] max_velocity_rpm: Maximum output angular velocity [RPM] * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] pos_b: Position of RW on the body fixed frame [m] - * @param [in] dead_time: Dead time of torque output [sec] - * @param [in] driving_lag_coef: Driving lag coefficients - * @param [in] coasting_lag_coef: Coasting lag coefficients + * @param [in] position_b_m: Position of RW on the body fixed frame [m] + * @param [in] dead_time_s: Dead time of torque output [sec] + * @param [in] driving_lag_coefficients: Driving lag coefficients + * @param [in] coasting_lag_coefficients: Coasting lag coefficients * @param [in] is_calc_jitter_enabled: Enable flag to calculate RW jitter * @param [in] is_log_jitter_enabled: Enable flag to log output RW jitter * @param [in] radial_force_harmonics_coefficients: Coefficients for radial force harmonics @@ -89,15 +89,15 @@ class RWModel : public Component, public ILoggable { * @param [in] bandwidth: Bandwidth of structural resonance * @param [in] considers_structural_resonance: Flag to consider structural resonance * @param [in] drive_flag: RW drive flag - * @param [in] init_velocity: Initial value of angular velocity of RW [rad/s] + * @param [in] init_velocity_rad_s: Initial value of angular velocity of RW [rad/s] */ RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - const double step_width_s, const double dt_main_routine, const double jitter_update_interval, const double inertia, const double max_torque, - const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> pos_b, const double dead_time, - const libra::Vector<3> driving_lag_coef, const libra::Vector<3> coasting_lag_coef, bool is_calc_jitter_enabled, bool is_log_jitter_enabled, - std::vector> radial_force_harmonics_coefficients, std::vector> radial_torque_harmonics_coefficients, - double structural_resonance_frequency_Hz, double damping_factor, double bandwidth, bool considers_structural_resonance, - const bool drive_flag = false, const double init_velocity = 0.0); + const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, + const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, + const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, + bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coefficients, + std::vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, + double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity_rad_s = 0.0); // Override functions for Component /** @@ -206,7 +206,7 @@ class RWModel : public Component, public ILoggable { // Internal variables for control delay std::vector acceleration_delay_buffer_; //!< Delay buffer for acceleration - double main_routine_time_steo_s_; //!< Period of execution of main routine [sec] + double main_routine_time_step_s_; //!< Period of execution of main routine [sec] // Output at RW frame double angular_acceleration_rad_s2_ = 0.0; //!< Output angular acceleration [rad/s2] diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 546e9511a..8480df75f 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -17,7 +17,7 @@ GravityGradient::GravityGradient(const double gravity_constant_m3_s2, const bool : SimpleDisturbance(is_calculation_enabled), gravity_constant_m3_s2_(gravity_constant_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - // TODO: use structure information to get inertia tensor + // TODO: use structure information to get rotor_inertia_kgm2 tensor CalcTorque_b_Nm(local_environment.GetCelestialInformation().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); } diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 15b4d4beb..ebb9af081 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -58,7 +58,7 @@ class Attitude : public ILoggable, public SimulationObject { inline double GetEnergy() const { return kinetic_energy_J_; } /** * @fn GetInertiaTensor - * @brief Return inertia tensor [kg m^2] + * @brief Return rotor_inertia_kgm2 tensor [kg m^2] */ inline libra::Matrix<3, 3> GetInertiaTensor() const { return inertia_tensor_kgm2_; } @@ -119,7 +119,7 @@ class Attitude : public ILoggable, public SimulationObject { libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] libra::Matrix<3, 3> inertia_tensor_kgm2_; //!< Inertia tensor of the spacecraft [kg m^2] TODO: Move to Structure - libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the inertia tensor + libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the rotor_inertia_kgm2 tensor libra::Vector<3> angular_momentum_spacecraft_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] libra::Vector<3> angular_momentum_reaction_wheel_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index dc7bc2d54..94c5f4718 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -19,7 +19,7 @@ class AttitudeRk4 : public Attitude { * @brief Constructor * @param [in] angular_velocity_b_rad_s: Initial value of spacecraft angular velocity of the body fixed frame [rad/s] * @param [in] quaternion_i2b: Initial value of attitude quaternion from the inertial frame to the body fixed frame - * @param [in] inertia_tensor_kgm2: Initial value of inertia tensor of the spacecraft [kg m^2] + * @param [in] inertia_tensor_kgm2: Initial value of rotor_inertia_kgm2 tensor of the spacecraft [kg m^2] * @param [in] torque_b_Nm: Initial torque acting on the spacecraft in the body fixed frame [Nm] * @param [in] propagation_step_s: Initial value of propagation step width [sec] * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index cc332ac54..3fcbb1a8e 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -20,7 +20,7 @@ ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, cons local_celestial_information_(local_celestial_information), orbit_(orbit) { quaternion_i2b_ = quaternion_i2b; - inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: inertia tensor should be initialized in the Attitude base class + inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: rotor_inertia_kgm2 tensor should be initialized in the Attitude base class inv_inertia_tensor_ = CalcInverseMatrix(inertia_tensor_kgm2_); Initialize(); diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 413ce0eac..278282ec9 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -123,7 +123,7 @@ class ControlledAttitude : public Attitude { * @fn CalcTargetDirection_i * @brief Calculate target direction from attitude control mode * @param [in] mode: Attitude control mode - * @return Target direction at the inertia frame0 + * @return Target direction at the rotor_inertia_kgm2 frame0 */ libra::Vector<3> CalcTargetDirection_i(AttitudeControlMode mode); /** From 442379172a940b6edc2b7135301d2c7fc20926c4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:11:03 +0100 Subject: [PATCH 0811/1086] Fix function arguments names --- src/components/real/aocs/reaction_wheel.cpp | 4 ++-- src/components/real/aocs/reaction_wheel.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 1bb50a4f3..2c3284f83 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -95,8 +95,8 @@ void RWModel::Initialize() { } } -void RWModel::MainRoutine(int count) { - UNUSED(count); +void RWModel::MainRoutine(const int time_count) { + UNUSED(time_count); CalcTorque(); } diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 0a56b483c..01a0d5375 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -104,7 +104,7 @@ class RWModel : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to output torque of normal RW */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; /** * @fn PowerOffRoutine * @brief Power off routine to stop actuation From 4c213a74be207f3d8a7b6d10ae61668e8f624b6f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:16:26 +0100 Subject: [PATCH 0812/1086] Add const --- src/components/real/aocs/reaction_wheel.cpp | 44 +++++++++++---------- src/components/real/aocs/reaction_wheel.hpp | 25 ++++++------ 2 files changed, 38 insertions(+), 31 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 2c3284f83..ac3cc10dd 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -17,13 +17,15 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, const int component_id, double step_width_s, - double main_routine_time_step_s, double jitter_update_interval_s, double rotor_inertia_kgm2, double max_torque_Nm, - double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> position_b_m, double dead_time_s, - libra::Vector<3> driving_lag_coefficients, libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, - bool is_log_jitter_enabled, vector> radial_force_harmonics_coefficients, - vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, - double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity_rad_s) +RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, + const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, + const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, + const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, + const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag, + const double init_velocity_rad_s) : Component(prescaler, clock_generator, fast_prescaler), component_id_(component_id), rotor_inertia_kgm2_(rotor_inertia_kgm2), @@ -45,13 +47,15 @@ RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_genera Initialize(); } -RWModel::RWModel(int prescaler, int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - double step_width_s, double main_routine_time_step_s, double jitter_update_interval_s, double rotor_inertia_kgm2, - double max_torque_Nm, double max_velocity_rpm, libra::Quaternion quaternion_b2c, libra::Vector<3> position_b_m, double dead_time_s, - libra::Vector<3> driving_lag_coefficients, libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, - bool is_log_jitter_enabled, vector> radial_force_harmonics_coefficients, - vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, - double bandwidth, bool considers_structural_resonance, bool drive_flag, double init_velocity_rad_s) +RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, + const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, + const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, + const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, + const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag, + const double init_velocity_rad_s) : Component(prescaler, clock_generator, power_port, fast_prescaler), component_id_(component_id), rotor_inertia_kgm2_(rotor_inertia_kgm2), @@ -159,19 +163,19 @@ const libra::Vector<3> RWModel::GetOutputTorqueB() const { } } -void RWModel::SetTargetTorqueRw(double torque_rw) { +void RWModel::SetTargetTorqueRw(const double torque_rw_Nm) { // Check Torque Limit double sign; - torque_rw > 0 ? sign = 1.0 : sign = -1.0; - if (abs(torque_rw) < max_torque_Nm_) { - target_acceleration_rad_s2_ = torque_rw / rotor_inertia_kgm2_; + torque_rw_Nm > 0 ? sign = 1.0 : sign = -1.0; + if (abs(torque_rw_Nm) < max_torque_Nm_) { + target_acceleration_rad_s2_ = torque_rw_Nm / rotor_inertia_kgm2_; } else { target_acceleration_rad_s2_ = sign * max_torque_Nm_ / rotor_inertia_kgm2_; } } -void RWModel::SetTargetTorqueBody(double torque_body) { SetTargetTorqueRw(-1.0 * torque_body); } +void RWModel::SetTargetTorqueBody(const double torque_b_Nm) { SetTargetTorqueRw(-1.0 * torque_b_Nm); } -void RWModel::SetVelocityLimitRpm(double velocity_limit_rpm) { +void RWModel::SetVelocityLimitRpm(const double velocity_limit_rpm) { if (velocity_limit_rpm > max_velocity_rpm_) { velocity_limit_rpm_ = max_velocity_rpm_; } else if (velocity_limit_rpm < -1.0 * max_velocity_rpm_) { diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 01a0d5375..b62712de4 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -57,10 +57,11 @@ class RWModel : public Component, public ILoggable { RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, const double dead_time_s, - const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, bool is_calc_jitter_enabled, - bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coefficients, - std::vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, - double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity_rad_s = 0.0); + const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, + const bool is_log_jitter_enabled, const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, + const double init_velocity_rad_s = 0.0); /** * @fn RWModel * @brief Constructor with power port @@ -95,9 +96,11 @@ class RWModel : public Component, public ILoggable { const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, - bool is_calc_jitter_enabled, bool is_log_jitter_enabled, std::vector> radial_force_harmonics_coefficients, - std::vector> radial_torque_harmonics_coefficients, double structural_resonance_frequency_Hz, double damping_factor, - double bandwidth, bool considers_structural_resonance, const bool drive_flag = false, const double init_velocity_rad_s = 0.0); + const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, + const double init_velocity_rad_s = 0.0); // Override functions for Component /** @@ -165,22 +168,22 @@ class RWModel : public Component, public ILoggable { * @fn SetTargetTorqueRw * @brief Set target torque on RW frame [Nm] */ - void SetTargetTorqueRw(double torque_rw); + void SetTargetTorqueRw(const double torque_rw_Nm); /** * @fn SetTargetTorqueBody * @brief Set target torque on body frame (opposite of RW frame) [Nm] */ - void SetTargetTorqueBody(double torque_body); + void SetTargetTorqueBody(const double torque_b_Nm); /** * @fn SetVelocityLimitRpm * @brief Set velocity limit [RPM] */ - void SetVelocityLimitRpm(double velocity_limit_rpm); + void SetVelocityLimitRpm(const double velocity_limit_rpm); /** * @fn SetDriveFlag * @brief Set drive flag */ - inline void SetDriveFlag(bool flag) { drive_flag_ = flag; }; + inline void SetDriveFlag(const bool flag) { drive_flag_ = flag; }; protected: // Fixed Parameters From 8fcff127b28bb4bd5d63609797a211a38d9d64f1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:19:36 +0100 Subject: [PATCH 0813/1086] Fix public function name --- src/components/real/aocs/reaction_wheel.cpp | 8 ++--- src/components/real/aocs/reaction_wheel.hpp | 32 +++++++++---------- .../sample_spacecraft/sample_components.cpp | 4 +-- 3 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index ac3cc10dd..1205223af 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -154,7 +154,7 @@ libra::Vector<3> RWModel::CalcTorque() { return output_torque_b_Nm_; } -const libra::Vector<3> RWModel::GetOutputTorqueB() const { +const libra::Vector<3> RWModel::GetOutputTorque_b_Nm() const { if (is_calculated_jitter_) { // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torque_b return output_torque_b_Nm_ - libra::OuterProduct(position_b_m_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); @@ -163,7 +163,7 @@ const libra::Vector<3> RWModel::GetOutputTorqueB() const { } } -void RWModel::SetTargetTorqueRw(const double torque_rw_Nm) { +void RWModel::SetTargetTorque_rw_Nm(const double torque_rw_Nm) { // Check Torque Limit double sign; torque_rw_Nm > 0 ? sign = 1.0 : sign = -1.0; @@ -173,9 +173,9 @@ void RWModel::SetTargetTorqueRw(const double torque_rw_Nm) { target_acceleration_rad_s2_ = sign * max_torque_Nm_ / rotor_inertia_kgm2_; } } -void RWModel::SetTargetTorqueBody(const double torque_b_Nm) { SetTargetTorqueRw(-1.0 * torque_b_Nm); } +void RWModel::SetTargetTorque_b_Nm(const double torque_b_Nm) { SetTargetTorque_rw_Nm(-1.0 * torque_b_Nm); } -void RWModel::SetVelocityLimitRpm(const double velocity_limit_rpm) { +void RWModel::SetVelocityLimit_rpm(const double velocity_limit_rpm) { if (velocity_limit_rpm > max_velocity_rpm_) { velocity_limit_rpm_ = max_velocity_rpm_; } else if (velocity_limit_rpm < -1.0 * max_velocity_rpm_) { diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index b62712de4..6f65ef2a3 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -133,52 +133,52 @@ class RWModel : public Component, public ILoggable { // Getter /** - * @fn GetOutputTorqueB + * @fn GetOutputTorque_b_Nm * @brief Return output torque in the body fixed frame [Nm] */ - const libra::Vector<3> GetOutputTorqueB() const; + const libra::Vector<3> GetOutputTorque_b_Nm() const; /** * @fn GetJitterForce_b_N * @brief Return output force by jitter in the body fixed frame [N] */ const libra::Vector<3> GetJitterForce_b_N() const { return rw_jitter_.GetJitterForce_b_N(); } /** - * @fn isMotorDrove + * @fn GetDriveFlag * @brief Return drive flag */ - inline bool isMotorDrove() const { return drive_flag_; }; + inline bool GetDriveFlag() const { return drive_flag_; }; /** - * @fn GetVelocityRad + * @fn GetAngularVelocity_rad_s * @brief Return angular velocity of RW rotor [rad/s] */ - inline double GetVelocityRad() const { return angular_velocity_rad_s_; }; + inline double GetAngularVelocity_rad_s() const { return angular_velocity_rad_s_; }; /** - * @fn GetVelocityRpm + * @fn GetAngularVelocity_rpm * @brief Return angular velocity of RW rotor [RPM] */ - inline double GetVelocityRpm() const { return angular_velocity_rpm_; }; + inline double GetAngularVelocity_rpm() const { return angular_velocity_rpm_; }; /** - * @fn GetAngMomB + * @fn GetAngularMomentum_b_Nms * @brief Return angular momentum of RW [Nms] */ - inline const libra::Vector<3> GetAngMomB() const { return angular_momentum_b_Nms_; }; + inline const libra::Vector<3> GetAngularMomentum_b_Nms() const { return angular_momentum_b_Nms_; }; // Setter /** - * @fn SetTargetTorqueRw + * @fn SetTargetTorque_rw_Nm * @brief Set target torque on RW frame [Nm] */ - void SetTargetTorqueRw(const double torque_rw_Nm); + void SetTargetTorque_rw_Nm(const double torque_rw_Nm); /** - * @fn SetTargetTorqueBody + * @fn SetTargetTorque_b_Nm * @brief Set target torque on body frame (opposite of RW frame) [Nm] */ - void SetTargetTorqueBody(const double torque_b_Nm); + void SetTargetTorque_b_Nm(const double torque_b_Nm); /** - * @fn SetVelocityLimitRpm + * @fn SetVelocityLimit_rpm * @brief Set velocity limit [RPM] */ - void SetVelocityLimitRpm(const double velocity_limit_rpm); + void SetVelocityLimit_rpm(const double velocity_limit_rpm); /** * @fn SetDriveFlag * @brief Set drive flag diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index c37c044d8..4ecd9f928 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -108,7 +108,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // actuator debug output // libra::Vector mag_moment_c{0.01}; // mag_torquer_->SetOutputMagneticMoment_c_Am2(mag_moment_c); - // rw_->SetTargetTorqueRw(0.01); + // rw_->SetTargetTorque_rw_Nm(0.01); // rw_->SetDriveFlag(true); // thruster_->SetDuty(0.9); @@ -159,7 +159,7 @@ libra::Vector<3> SampleComponents::GenerateForce_N_b() { libra::Vector<3> SampleComponents::GenerateTorque_Nm_b() { libra::Vector<3> torque_Nm_b_(0.0); torque_Nm_b_ += mag_torquer_->GetOutputTorque_b_Nm(); - torque_Nm_b_ += rw_->GetOutputTorqueB(); + torque_Nm_b_ += rw_->GetOutputTorque_b_Nm(); torque_Nm_b_ += thruster_->GetTorqueB(); torque_Nm_b_ += torque_generator_->GetGeneratedTorque_b_Nm(); return torque_Nm_b_; From 03df20b968a836f2bad4dbc2ad89ffe76294a226 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:20:15 +0100 Subject: [PATCH 0814/1086] Rename RWModel to ReactionWheel --- .../real/aocs/initialize_reaction_wheel.cpp | 26 ++++---- .../real/aocs/initialize_reaction_wheel.hpp | 6 +- src/components/real/aocs/reaction_wheel.cpp | 60 ++++++++++--------- src/components/real/aocs/reaction_wheel.hpp | 45 +++++++------- .../sample_spacecraft/sample_components.cpp | 4 +- .../sample_spacecraft/sample_components.hpp | 4 +- 6 files changed, 74 insertions(+), 71 deletions(-) diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index 67962cf1f..0281b38df 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -98,29 +98,29 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double } } // namespace -RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { +ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, main_routine_time_step_s, jitter_update_interval_s, - rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, ordinary_lag_coef, - coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, - radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, - drive_flag, init_velocity_rad_s); + ReactionWheel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, main_routine_time_step_s, jitter_update_interval_s, + rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, ordinary_lag_coef, + coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, + radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, + considers_structural_resonance, drive_flag, init_velocity_rad_s); return rwmodel; } -RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, - double compo_update_step) { +ReactionWheel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, + double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); power_port->InitializeWithInitializeFile(file_name); - RWModel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width_s, main_routine_time_step_s, - jitter_update_interval_s, rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, - ordinary_lag_coef, coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, radial_force_harmonics_coefficients, - radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, bandwidth, considers_structural_resonance, - drive_flag, init_velocity_rad_s); + ReactionWheel rwmodel(prescaler, fast_prescaler, clock_generator, power_port, actuator_id, step_width_s, main_routine_time_step_s, + jitter_update_interval_s, rotor_inertia_kgm2, max_torque_Nm, max_velocity, quaternion_b2c, position_b_m, dead_time_s, + ordinary_lag_coef, coasting_lag_coefficients, is_calc_jitter_enabled, is_log_jitter_enabled, + radial_force_harmonics_coefficients, radial_torque_harmonics_coefficients, structural_resonance_frequency_Hz, damping_factor, + bandwidth, considers_structural_resonance, drive_flag, init_velocity_rad_s); return rwmodel; } diff --git a/src/components/real/aocs/initialize_reaction_wheel.hpp b/src/components/real/aocs/initialize_reaction_wheel.hpp index 97696aa95..20b45caa1 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.hpp +++ b/src/components/real/aocs/initialize_reaction_wheel.hpp @@ -17,7 +17,7 @@ * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step); +ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step); /** * @fn InitRWModel * @brief Initialize functions for reaction wheel with power port @@ -28,7 +28,7 @@ RWModel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::strin * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -RWModel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, - double compo_update_step); +ReactionWheel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, + double compo_update_step); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ diff --git a/src/components/real/aocs/reaction_wheel.cpp b/src/components/real/aocs/reaction_wheel.cpp index 1205223af..9327ede53 100644 --- a/src/components/real/aocs/reaction_wheel.cpp +++ b/src/components/real/aocs/reaction_wheel.cpp @@ -17,15 +17,16 @@ static double rpm2angularVelocity(double rpm) { return rpm * libra::tau / 60.0; static double angularVelocity2rpm(double angular_velocity) { return angular_velocity * 60.0 / libra::tau; } -RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, - const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, - const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, - const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, - const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, - const std::vector> radial_force_harmonics_coefficients, - const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag, - const double init_velocity_rad_s) +ReactionWheel::ReactionWheel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, + const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, + const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, + const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, const double dead_time_s, + const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, + const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, + const double structural_resonance_frequency_Hz, const double damping_factor, const double bandwidth, + const bool considers_structural_resonance, const bool drive_flag, const double init_velocity_rad_s) : Component(prescaler, clock_generator, fast_prescaler), component_id_(component_id), rotor_inertia_kgm2_(rotor_inertia_kgm2), @@ -47,15 +48,16 @@ RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator * Initialize(); } -RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, - const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, - const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, - const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, - const std::vector> radial_force_harmonics_coefficients, - const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag, - const double init_velocity_rad_s) +ReactionWheel::ReactionWheel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, + const int component_id, const double step_width_s, const double main_routine_time_step_s, + const double jitter_update_interval_s, const double rotor_inertia_kgm2, const double max_torque_Nm, + const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, + const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, + const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, + const double structural_resonance_frequency_Hz, const double damping_factor, const double bandwidth, + const bool considers_structural_resonance, const bool drive_flag, const double init_velocity_rad_s) : Component(prescaler, clock_generator, power_port, fast_prescaler), component_id_(component_id), rotor_inertia_kgm2_(rotor_inertia_kgm2), @@ -77,7 +79,7 @@ RWModel::RWModel(const int prescaler, const int fast_prescaler, ClockGenerator * Initialize(); } -void RWModel::Initialize() { +void ReactionWheel::Initialize() { rotation_axis_c_ = libra::Vector<3>(0.0); rotation_axis_c_[2] = 1.0; rotation_axis_b_ = quaternion_b2c_.InverseFrameConversion(rotation_axis_c_); @@ -99,18 +101,18 @@ void RWModel::Initialize() { } } -void RWModel::MainRoutine(const int time_count) { +void ReactionWheel::MainRoutine(const int time_count) { UNUSED(time_count); CalcTorque(); } -void RWModel::PowerOffRoutine() { drive_flag_ = 0; } +void ReactionWheel::PowerOffRoutine() { drive_flag_ = 0; } // Jitter calculation -void RWModel::FastUpdate() { rw_jitter_.CalcJitter(angular_velocity_rad_s_); } +void ReactionWheel::FastUpdate() { rw_jitter_.CalcJitter(angular_velocity_rad_s_); } -libra::Vector<3> RWModel::CalcTorque() { +libra::Vector<3> ReactionWheel::CalcTorque() { double pre_angular_velocity_rad = angular_velocity_rad_s_; if (!drive_flag_) // RW power off -> coasting mode { @@ -154,7 +156,7 @@ libra::Vector<3> RWModel::CalcTorque() { return output_torque_b_Nm_; } -const libra::Vector<3> RWModel::GetOutputTorque_b_Nm() const { +const libra::Vector<3> ReactionWheel::GetOutputTorque_b_Nm() const { if (is_calculated_jitter_) { // Add jitter_force_b_N_-derived torque and jitter_torque_b_Nm_ to output_torque_b return output_torque_b_Nm_ - libra::OuterProduct(position_b_m_, rw_jitter_.GetJitterForce_b_N()) - rw_jitter_.GetJitterTorque_b_Nm(); @@ -163,7 +165,7 @@ const libra::Vector<3> RWModel::GetOutputTorque_b_Nm() const { } } -void RWModel::SetTargetTorque_rw_Nm(const double torque_rw_Nm) { +void ReactionWheel::SetTargetTorque_rw_Nm(const double torque_rw_Nm) { // Check Torque Limit double sign; torque_rw_Nm > 0 ? sign = 1.0 : sign = -1.0; @@ -173,9 +175,9 @@ void RWModel::SetTargetTorque_rw_Nm(const double torque_rw_Nm) { target_acceleration_rad_s2_ = sign * max_torque_Nm_ / rotor_inertia_kgm2_; } } -void RWModel::SetTargetTorque_b_Nm(const double torque_b_Nm) { SetTargetTorque_rw_Nm(-1.0 * torque_b_Nm); } +void ReactionWheel::SetTargetTorque_b_Nm(const double torque_b_Nm) { SetTargetTorque_rw_Nm(-1.0 * torque_b_Nm); } -void RWModel::SetVelocityLimit_rpm(const double velocity_limit_rpm) { +void ReactionWheel::SetVelocityLimit_rpm(const double velocity_limit_rpm) { if (velocity_limit_rpm > max_velocity_rpm_) { velocity_limit_rpm_ = max_velocity_rpm_; } else if (velocity_limit_rpm < -1.0 * max_velocity_rpm_) { @@ -186,7 +188,7 @@ void RWModel::SetVelocityLimit_rpm(const double velocity_limit_rpm) { return; } -std::string RWModel::GetLogHeader() const { +std::string ReactionWheel::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "rw" + std::to_string(static_cast(component_id_)) + "_"; @@ -203,7 +205,7 @@ std::string RWModel::GetLogHeader() const { return str_tmp; } -std::string RWModel::GetLogValue() const { +std::string ReactionWheel::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(angular_velocity_rad_s_); diff --git a/src/components/real/aocs/reaction_wheel.hpp b/src/components/real/aocs/reaction_wheel.hpp index 6f65ef2a3..427cff2ce 100644 --- a/src/components/real/aocs/reaction_wheel.hpp +++ b/src/components/real/aocs/reaction_wheel.hpp @@ -18,14 +18,14 @@ #include "reaction_wheel_ode.hpp" /* - * @class RWModel + * @class ReactionWheel * @brief Class to emulate Reaction Wheel * @note For one reaction wheel */ -class RWModel : public Component, public ILoggable { +class ReactionWheel : public Component, public ILoggable { public: /** - * @fn RWModel + * @fn ReactionWheel * @brief Constructor without power port * @note TODO: argument is too long * @param [in] prescaler: Frequency scale factor for update @@ -54,16 +54,17 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity_rad_s: Initial value of angular velocity of RW */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, - const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, const double max_torque_Nm, - const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, const double dead_time_s, - const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, - const bool is_log_jitter_enabled, const std::vector> radial_force_harmonics_coefficients, - const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, - const double init_velocity_rad_s = 0.0); - /** - * @fn RWModel + ReactionWheel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, const int component_id, const double step_width_s, + const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, + const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, + const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, + const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, + const double init_velocity_rad_s = 0.0); + /** + * @fn ReactionWheel * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] fast_prescaler: Frequency scale factor for fast update @@ -92,15 +93,15 @@ class RWModel : public Component, public ILoggable { * @param [in] drive_flag: RW drive flag * @param [in] init_velocity_rad_s: Initial value of angular velocity of RW [rad/s] */ - RWModel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, - const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, const double rotor_inertia_kgm2, - const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, const libra::Vector<3> position_b_m, - const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, const libra::Vector<3> coasting_lag_coefficients, - const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, - const std::vector> radial_force_harmonics_coefficients, - const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, - const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, - const double init_velocity_rad_s = 0.0); + ReactionWheel(const int prescaler, const int fast_prescaler, ClockGenerator *clock_generator, PowerPort *power_port, const int component_id, + const double step_width_s, const double main_routine_time_step_s, const double jitter_update_interval_s, + const double rotor_inertia_kgm2, const double max_torque_Nm, const double max_velocity_rpm, const libra::Quaternion quaternion_b2c, + const libra::Vector<3> position_b_m, const double dead_time_s, const libra::Vector<3> driving_lag_coefficients, + const libra::Vector<3> coasting_lag_coefficients, const bool is_calc_jitter_enabled, const bool is_log_jitter_enabled, + const std::vector> radial_force_harmonics_coefficients, + const std::vector> radial_torque_harmonics_coefficients, const double structural_resonance_frequency_Hz, + const double damping_factor, const double bandwidth, const bool considers_structural_resonance, const bool drive_flag = false, + const double init_velocity_rad_s = 0.0); // Override functions for Component /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 4ecd9f928..d1fde030f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -62,8 +62,8 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - rw_ = new RWModel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), - glo_env_->GetSimulationTime().GetComponentStepTime_s())); + rw_ = new ReactionWheel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), + glo_env_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 448accb27..063ef505a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -38,7 +38,7 @@ class STT; class SunSensor; class GnssReceiver; class Magnetorquer; -class RWModel; +class ReactionWheel; class SimpleThruster; class ForceGenerator; class TorqueGenerator; @@ -93,7 +93,7 @@ class SampleComponents : public InstalledComponents { SunSensor* sun_sensor_; //!< Sun sensor GnssReceiver* gnss_; //!< GNSS receiver Magnetorquer* mag_torquer_; //!< Magnetorquer - RWModel* rw_; //!< Reaction Wheel + ReactionWheel* rw_; //!< Reaction Wheel SimpleThruster* thruster_; //!< Thruster ForceGenerator* force_generator_; //!< Ideal Force Generator TorqueGenerator* torque_generator_; //!< Ideal Torque Generator From de5674c53183836b4c54b51e6cc8a3d0f5b19f6a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:29:19 +0100 Subject: [PATCH 0815/1086] Fix private variables names --- src/components/real/aocs/star_sensor.cpp | 116 +++++++++++----------- src/components/real/aocs/star_sensor.hpp | 52 +++++----- src/components/real/mission/telescope.cpp | 24 ++--- src/components/real/mission/telescope.hpp | 10 +- 4 files changed, 101 insertions(+), 101 deletions(-) diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 169d2ce82..15aeede32 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -22,20 +22,20 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int compone : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), - rot_(global_randomization.MakeSeed()), - n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), - n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), - pos_(0), - step_time_(step_time), + rotation_noise_(global_randomization.MakeSeed()), + orthogonal_direction_noise_(0.0, sigma_ortho, global_randomization.MakeSeed()), + sight_direction_noise_(0.0, sigma_sight, global_randomization.MakeSeed()), + buffer_position_(0), + step_time_s_(step_time), output_delay_(output_delay), output_interval_(output_interval), - count_(0), - sun_forbidden_angle_(sun_forbidden_angle), - earth_forbidden_angle_(earth_forbidden_angle), - moon_forbidden_angle_(moon_forbidden_angle), - capture_rate_(capture_rate), + update_count_(0), + sun_forbidden_angle_rad_(sun_forbidden_angle), + earth_forbidden_angle_rad_(earth_forbidden_angle), + moon_forbidden_angle_rad_(moon_forbidden_angle), + capture_rate_limit_rad_s_(capture_rate), dynamics_(dynamics), - local_env_(local_env) { + local_environment_(local_env) { Initialize(); } STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, @@ -45,80 +45,80 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_ : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), - rot_(global_randomization.MakeSeed()), - n_ortho_(0.0, sigma_ortho, global_randomization.MakeSeed()), - n_sight_(0.0, sigma_sight, global_randomization.MakeSeed()), - pos_(0), - step_time_(step_time), + rotation_noise_(global_randomization.MakeSeed()), + orthogonal_direction_noise_(0.0, sigma_ortho, global_randomization.MakeSeed()), + sight_direction_noise_(0.0, sigma_sight, global_randomization.MakeSeed()), + buffer_position_(0), + step_time_s_(step_time), output_delay_(output_delay), output_interval_(output_interval), - count_(0), - sun_forbidden_angle_(sun_forbidden_angle), - earth_forbidden_angle_(earth_forbidden_angle), - moon_forbidden_angle_(moon_forbidden_angle), - capture_rate_(capture_rate), + update_count_(0), + sun_forbidden_angle_rad_(sun_forbidden_angle), + earth_forbidden_angle_rad_(earth_forbidden_angle), + moon_forbidden_angle_rad_(moon_forbidden_angle), + capture_rate_limit_rad_s_(capture_rate), dynamics_(dynamics), - local_env_(local_env) { + local_environment_(local_env) { Initialize(); } void STT::Initialize() { - q_stt_i2c_ = Quaternion(0.0, 0.0, 0.0, 1.0); + measured_quaternion_i2c_ = Quaternion(0.0, 0.0, 0.0, 1.0); // Decide delay buffer size - MAX_DELAY = int(output_delay_ * 2 / step_time_); - if (MAX_DELAY <= 0) MAX_DELAY = 1; - vector temp(MAX_DELAY); - q_buffer_ = temp; + max_delay_ = int(output_delay_ * 2 / step_time_s_); + if (max_delay_ <= 0) max_delay_ = 1; + vector temp(max_delay_); + delay_buffer_ = temp; // Initialize delay buffer - for (int i = 0; i < MAX_DELAY; ++i) { - q_buffer_[i] = q_stt_i2c_; + for (int i = 0; i < max_delay_; ++i) { + delay_buffer_[i] = measured_quaternion_i2c_; } - sight_ = Vector<3>(0.0); - ortho1_ = Vector<3>(0.0); - ortho2_ = Vector<3>(0.0); - sight_[0] = 1.0; //(1,0,0)@Component coordinates, viewing direction - ortho1_[1] = 1.0; //(0,1,0)@Component coordinates, line-of-sight orthogonal direction - ortho2_[2] = 1.0; //(0,0,1)@Component coordinates, line-of-sight orthogonal direction + sight_direction_c_ = Vector<3>(0.0); + first_orthogonal_direction_c = Vector<3>(0.0); + second_orthogonal_direction_c = Vector<3>(0.0); + sight_direction_c_[0] = 1.0; //(1,0,0)@Component coordinates, viewing direction + first_orthogonal_direction_c[1] = 1.0; //(0,1,0)@Component coordinates, line-of-sight orthogonal direction + second_orthogonal_direction_c[2] = 1.0; //(0,0,1)@Component coordinates, line-of-sight orthogonal direction error_flag_ = true; } Quaternion STT::measure(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { update(local_celes_info, attinfo); // update delay buffer - if (count_ == 0) { - int hist = pos_ - output_delay_ - 1; + if (update_count_ == 0) { + int hist = buffer_position_ - output_delay_ - 1; if (hist < 0) { - hist += MAX_DELAY; + hist += max_delay_; } - q_stt_i2c_ = q_buffer_[hist]; + measured_quaternion_i2c_ = delay_buffer_[hist]; } - if (++count_ == output_interval_) { - count_ = 0; + if (++update_count_ == output_interval_) { + update_count_ = 0; } - return q_stt_i2c_; + return measured_quaternion_i2c_; } void STT::update(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { Quaternion quaternion_i2b = attinfo->GetQuaternion_i2b(); // Read true value Quaternion q_stt_temp = quaternion_i2b * quaternion_b2c_; // Convert to component frame // Add noise on sight direction - Quaternion q_sight(sight_, n_sight_); + Quaternion q_sight(sight_direction_c_, sight_direction_noise_); // Random noise on orthogonal direction of sight. Range [0:2pi] - double rot = libra::tau * double(rot_); + double rot = libra::tau * double(rotation_noise_); // Calc observation error on orthogonal direction of sight - Vector<3> rot_axis = cos(rot) * ortho1_ + sin(rot) * ortho2_; - Quaternion q_ortho(rot_axis, n_ortho_); + Vector<3> rot_axis = cos(rot) * first_orthogonal_direction_c + sin(rot) * second_orthogonal_direction_c; + Quaternion q_ortho(rot_axis, orthogonal_direction_noise_); // Judge errors AllJudgement(local_celes_info, attinfo); // Calc observed quaternion: Inertial frame → STT frame → Rotation around // sight →Rotation around orthogonal direction - q_buffer_[pos_] = q_stt_temp * q_sight * q_ortho; + delay_buffer_[buffer_position_] = q_stt_temp * q_sight * q_ortho; // Update delay buffer position - ++pos_; - pos_ %= MAX_DELAY; + ++buffer_position_; + buffer_position_ %= max_delay_; } void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { @@ -135,9 +135,9 @@ void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const int STT::SunJudgement(const libra::Vector<3>& sun_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_); + Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double sun_angle_rad = CalAngleVect_rad(sun_b, sight_b); - if (sun_angle_rad < sun_forbidden_angle_) + if (sun_angle_rad < sun_forbidden_angle_rad_) return 1; else return 0; @@ -145,12 +145,12 @@ int STT::SunJudgement(const libra::Vector<3>& sun_b) { int STT::EarthJudgement(const libra::Vector<3>& earth_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_); + Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge double earth_center_angle_rad = CalAngleVect_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight double earth_edge_angle_rad = earth_center_angle_rad - earth_size_rad; // angles between sat<->earth_edge & sat_sight - if (earth_edge_angle_rad < earth_forbidden_angle_) + if (earth_edge_angle_rad < earth_forbidden_angle_rad_) return 1; else return 0; @@ -158,9 +158,9 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { int STT::MoonJudgement(const libra::Vector<3>& moon_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_); + Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double moon_angle_rad = CalAngleVect_rad(moon_b, sight_b); - if (moon_angle_rad < moon_forbidden_angle_) + if (moon_angle_rad < moon_forbidden_angle_rad_) return 1; else return 0; @@ -168,7 +168,7 @@ int STT::MoonJudgement(const libra::Vector<3>& moon_b) { int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b) { double omega_norm = CalcNorm(omega_b); - if (omega_norm > capture_rate_) + if (omega_norm > capture_rate_limit_rad_s_) return 1; else return 0; @@ -188,7 +188,7 @@ std::string STT::GetLogHeader() const { std::string STT::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteQuaternion(q_stt_i2c_); + str_tmp += WriteQuaternion(measured_quaternion_i2c_); str_tmp += WriteScalar(double(error_flag_)); return str_tmp; @@ -207,5 +207,5 @@ double STT::CalAngleVect_rad(const Vector<3>& vect1, const Vector<3>& vect2) { void STT::MainRoutine(int count) { UNUSED(count); - measure(&(local_env_->GetCelestialInformation()), &(dynamics_->GetAttitude())); + measure(&(local_environment_->GetCelestialInformation()), &(dynamics_->GetAttitude())); } diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 2a598f045..1fe7b10e0 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -34,7 +34,7 @@ class STT : public Component, public ILoggable { * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] * @param [in] step_time: Step time for delay calculation [sec] - * @param [in] output_delay: Output delay [0, MAX_DELAY] [step_sec] + * @param [in] output_delay: Output delay [0, max_delay_] [step_sec] * @param [in] output_interval: Output interval [step_sec] * @param [in] sun_forbidden_angle: Sun forbidden angle [rad] * @param [in] earth_forbidden_angle: Earth forbidden angle [rad] @@ -58,7 +58,7 @@ class STT : public Component, public ILoggable { * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] * @param [in] step_time: Step time for delay calculation [sec] - * @param [in] output_delay: Output delay [0, MAX_DELAY] [step_sec] + * @param [in] output_delay: Output delay [0, max_delay_] [step_sec] * @param [in] output_interval: Output interval [step_sec] * @param [in] sun_forbidden_angle: Sun forbidden angle [rad] * @param [in] earth_forbidden_angle: Earth forbidden angle [rad] @@ -95,7 +95,7 @@ class STT : public Component, public ILoggable { * @fn GetObsQuaternion * @brief Return observed quaternion from the inertial frame to the component frame */ - inline const libra::Quaternion GetObsQuaternion() const { return q_stt_i2c_; }; + inline const libra::Quaternion GetObsQuaternion() const { return measured_quaternion_i2c_; }; /** * @fn GetErrorFlag * @brief Return error flag @@ -104,37 +104,37 @@ class STT : public Component, public ILoggable { protected: // STT general parameters - const int component_id_; //!< Sensor ID - libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame - libra::Quaternion q_stt_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion - libra::Vector<3> sight_; //!< Sight direction vector at component frame - libra::Vector<3> ortho1_; //!< The first orthogonal direction of sight at component frame - libra::Vector<3> ortho2_; //!< The second orthogonal direction of sight at component frame + const int component_id_; //!< Sensor ID + libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame + libra::Quaternion measured_quaternion_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion + libra::Vector<3> sight_direction_c_; //!< Sight direction vector at component frame + libra::Vector<3> first_orthogonal_direction_c; //!< The first orthogonal direction of sight at component frame + libra::Vector<3> second_orthogonal_direction_c; //!< The second orthogonal direction of sight at component frame // Noise parameters - libra::MinimalStandardLcgWithShuffle rot_; //!< Randomize object for orthogonal direction - libra::NormalRand n_ortho_; //!< Random noise for orthogonal direction of sight [rad] - libra::NormalRand n_sight_; //!< Random noise for sight direction [rad] + 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 // Delay emulation parameters - int MAX_DELAY; //!< Max delay - std::vector q_buffer_; //!< Buffer of quaternion for delay emulation - int pos_; //!< Buffer position - double step_time_; //!< Step time for delay calculation [sec] - unsigned int output_delay_; //!< Output delay [0, MAX_DELAY] [step_sec] - unsigned int output_interval_; //!< Output interval [step_sec] - std::size_t count_; //!< Output update counter + int max_delay_; //!< Max delay + std::vector delay_buffer_; //!< Buffer of quaternion for delay emulation + int buffer_position_; //!< Buffer position + double step_time_s_; //!< Step time for delay calculation [sec] + unsigned int output_delay_; //!< Output delay [0, max_delay_] [step_sec] + unsigned int output_interval_; //!< Output interval [step_sec] + std::size_t update_count_; //!< Output update counter // observation error parameters - bool error_flag_; //!< Error flag. true: Error, false: No error - double sun_forbidden_angle_; //!< Sun forbidden angle [rad] - double earth_forbidden_angle_; //!< Earth forbidden angle [rad] - double moon_forbidden_angle_; //!< Moon forbidden angle [rad] - double capture_rate_; //!< Angular rate limit to get correct attitude [rad/s] + bool error_flag_; //!< Error flag. true: Error, false: No error + double sun_forbidden_angle_rad_; //!< Sun forbidden angle [rad] + double earth_forbidden_angle_rad_; //!< Earth forbidden angle [rad] + double moon_forbidden_angle_rad_; //!< Moon forbidden angle [rad] + double capture_rate_limit_rad_s_; //!< Angular rate limit to get correct attitude [rad/s] // Observed variables - const Dynamics* dynamics_; //!< Dynamics information - const LocalEnvironment* local_env_; //!< Local environment information + const Dynamics* dynamics_; //!< Dynamics information + const LocalEnvironment* local_environment_; //!< Local environment information // Internal functions /** diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 945cc5e71..51567958a 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -17,9 +17,9 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern const LocalCelestialInformation* local_celes_info) : Component(1, clock_generator), quaternion_b2c_(quaternion_b2c), - sun_forbidden_angle_(sun_forbidden_angle), - earth_forbidden_angle_(earth_forbidden_angle), - moon_forbidden_angle_(moon_forbidden_angle), + sun_forbidden_angle_rad_(sun_forbidden_angle), + earth_forbidden_angle_rad_(earth_forbidden_angle), + moon_forbidden_angle_rad_(moon_forbidden_angle), x_num_of_pix_(x_num_of_pix), y_num_of_pix_(y_num_of_pix), x_fov_par_pix_(x_fov_par_pix), @@ -37,8 +37,8 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern assert(x_field_of_view_rad < libra::pi_2); // Avoid the case that the field of view is over 90 degrees assert(y_field_of_view_rad < libra::pi_2); - sight_ = Vector<3>(0); - sight_[0] = 1; // (1,0,0) at component frame, Sight direction vector + sight_direction_c_ = Vector<3>(0); + sight_direction_c_[0] = 1; // (1,0,0) at component frame, Sight direction vector // Set 0 when t=0 for (size_t i = 0; i < num_of_logged_stars_; i++) { @@ -59,9 +59,9 @@ Telescope::~Telescope() {} void Telescope::MainRoutine(int count) { UNUSED(count); // Check forbidden angle - is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_); - is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_); - is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_); + is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_rad_); + is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_rad_); + is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_rad_); // Position calculation of celestial bodies from CelesInfo Observe(sun_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("SUN")); Observe(earth_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH")); @@ -73,15 +73,15 @@ void Telescope::MainRoutine(int count) { // sun_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); // earth_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); // moon_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("MOON")); - // angle_sun = CalcAngleTwoVectors_rad(sight_, sun_pos_c) * 180/libra::pi; - // angle_earth = CalcAngleTwoVectors_rad(sight_, earth_pos_c) * 180 / libra::pi; angle_moon = CalcAngleTwoVectors_rad(sight_, moon_pos_c) * 180 / - // libra::pi; + // angle_sun = CalcAngleTwoVectors_rad(sight_direction_c_, sun_pos_c) * 180/libra::pi; + // angle_earth = CalcAngleTwoVectors_rad(sight_direction_c_, earth_pos_c) * 180 / libra::pi; angle_moon = + // CalcAngleTwoVectors_rad(sight_direction_c_, moon_pos_c) * 180 / libra::pi; //****************************************************************************** } bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_); + Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double angle_rad = libra::CalcAngleTwoVectors_rad(target_b, sight_b); if (angle_rad < forbidden_angle) { return true; diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 6751717ef..2d43bd823 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -43,12 +43,12 @@ class Telescope : public Component, public ILoggable { protected: private: - libra::Quaternion quaternion_b2c_; //!< Quaternion from the body frame to component frame - libra::Vector<3> sight_; //!< Sight direction vector in the component frame + libra::Quaternion quaternion_b2c_; //!< Quaternion from the body frame to component frame + libra::Vector<3> sight_direction_c_; //!< Sight direction vector in the component frame - double sun_forbidden_angle_; //!< Sun forbidden angle [rad] - double earth_forbidden_angle_; //!< Earth forbidden angle [rad] - double moon_forbidden_angle_; //!< Moon forbidden angle [rad] + double sun_forbidden_angle_rad_; //!< Sun forbidden angle [rad] + double earth_forbidden_angle_rad_; //!< Earth forbidden angle [rad] + double moon_forbidden_angle_rad_; //!< Moon forbidden angle [rad] int x_num_of_pix_; //!< Number of pixel on X-axis in the image plane int y_num_of_pix_; //!< Number of pixel on Y-axis in the image plane From cd5ea09670024d64130ca31e759d11d1c0e5da49 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:31:31 +0100 Subject: [PATCH 0816/1086] Fix private function argument name --- .../real/aocs/initialize_sun_sensor.cpp | 8 ++-- .../real/aocs/initialize_sun_sensor.hpp | 4 +- src/components/real/aocs/star_sensor.cpp | 38 +++++++++---------- src/components/real/aocs/star_sensor.hpp | 30 +++++++-------- src/components/real/aocs/sun_sensor.cpp | 8 ++-- src/components/real/aocs/sun_sensor.hpp | 8 ++-- .../real/mission/initialize_telescope.cpp | 4 +- .../real/mission/initialize_telescope.hpp | 4 +- src/components/real/mission/telescope.cpp | 4 +- src/components/real/mission/telescope.hpp | 2 +- .../power/initialize_solar_array_panel.cpp | 4 +- .../power/initialize_solar_array_panel.hpp | 4 +- .../real/power/solar_array_panel.cpp | 8 ++-- .../real/power/solar_array_panel.hpp | 8 ++-- 14 files changed, 67 insertions(+), 67 deletions(-) diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index 28fd52111..b9e5bbb24 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -11,7 +11,7 @@ #include "library/initialize/initialize_file_access.hpp" SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info) { + const LocalCelestialInformation* local_celestial_information) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); @@ -39,12 +39,12 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string intensity_lower_threshold_percent = ss_conf.ReadDouble(Section, "intensity_lower_threshold_percent"); SunSensor ss(prescaler, clock_generator, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, - srp, local_celes_info); + srp, local_celestial_information); return ss; } SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int ss_id, std::string file_name, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info) { + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); @@ -74,6 +74,6 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, power_port->InitializeWithInitializeFile(file_name); SunSensor ss(prescaler, clock_generator, power_port, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, - intensity_lower_threshold_percent, srp, local_celes_info); + intensity_lower_threshold_percent, srp, local_celestial_information); return ss; } diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index ac398a51c..4da7194f1 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -18,7 +18,7 @@ * @param [in] local_env: Local environment information */ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info); + const LocalCelestialInformation* local_celestial_information); /** * @fn InitSunSensor * @brief Initialize functions for sun sensor with power port @@ -30,6 +30,6 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] local_env: Local environment information */ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celes_info); + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 15aeede32..b1533d5e5 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -84,8 +84,8 @@ void STT::Initialize() { error_flag_ = true; } -Quaternion STT::measure(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { - update(local_celes_info, attinfo); // update delay buffer +Quaternion STT::measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { + update(local_celestial_information, attitude); // update delay buffer if (update_count_ == 0) { int hist = buffer_position_ - output_delay_ - 1; if (hist < 0) { @@ -100,9 +100,9 @@ Quaternion STT::measure(const LocalCelestialInformation* local_celes_info, const return measured_quaternion_i2c_; } -void STT::update(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { - Quaternion quaternion_i2b = attinfo->GetQuaternion_i2b(); // Read true value - Quaternion q_stt_temp = quaternion_i2b * quaternion_b2c_; // Convert to component frame +void STT::update(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { + Quaternion quaternion_i2b = attitude->GetQuaternion_i2b(); // Read true value + Quaternion q_stt_temp = quaternion_i2b * quaternion_b2c_; // Convert to component frame // Add noise on sight direction Quaternion q_sight(sight_direction_c_, sight_direction_noise_); // Random noise on orthogonal direction of sight. Range [0:2pi] @@ -111,7 +111,7 @@ void STT::update(const LocalCelestialInformation* local_celes_info, const Attitu Vector<3> rot_axis = cos(rot) * first_orthogonal_direction_c + sin(rot) * second_orthogonal_direction_c; Quaternion q_ortho(rot_axis, orthogonal_direction_noise_); // Judge errors - AllJudgement(local_celes_info, attinfo); + AllJudgement(local_celestial_information, attitude); // Calc observed quaternion: Inertial frame → STT frame → Rotation around // sight →Rotation around orthogonal direction @@ -121,12 +121,12 @@ void STT::update(const LocalCelestialInformation* local_celes_info, const Attitu buffer_position_ %= max_delay_; } -void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo) { +void STT::AllJudgement(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { int judgement = 0; - judgement = SunJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("SUN")); - judgement += EarthJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("EARTH")); - judgement += MoonJudgement(local_celes_info->GetPositionFromSpacecraft_b_m("MOON")); - judgement += CaptureRateJudgement(attinfo->GetOmega_b()); + judgement = SunJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("SUN")); + judgement += EarthJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("EARTH")); + judgement += MoonJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("MOON")); + judgement += CaptureRateJudgement(attitude->GetOmega_b()); if (judgement > 0) error_flag_ = true; else @@ -136,7 +136,7 @@ void STT::AllJudgement(const LocalCelestialInformation* local_celes_info, const int STT::SunJudgement(const libra::Vector<3>& sun_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); - double sun_angle_rad = CalAngleVect_rad(sun_b, sight_b); + double sun_angle_rad = CalAngleVector_rad(sun_b, sight_b); if (sun_angle_rad < sun_forbidden_angle_rad_) return 1; else @@ -148,7 +148,7 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge - double earth_center_angle_rad = CalAngleVect_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight + double earth_center_angle_rad = CalAngleVector_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight double earth_edge_angle_rad = earth_center_angle_rad - earth_size_rad; // angles between sat<->earth_edge & sat_sight if (earth_edge_angle_rad < earth_forbidden_angle_rad_) return 1; @@ -159,15 +159,15 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { int STT::MoonJudgement(const libra::Vector<3>& moon_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); - double moon_angle_rad = CalAngleVect_rad(moon_b, sight_b); + double moon_angle_rad = CalAngleVector_rad(moon_b, sight_b); if (moon_angle_rad < moon_forbidden_angle_rad_) return 1; else return 0; } -int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b) { - double omega_norm = CalcNorm(omega_b); +int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s) { + double omega_norm = CalcNorm(omega_b_rad_s); if (omega_norm > capture_rate_limit_rad_s_) return 1; else @@ -194,10 +194,10 @@ std::string STT::GetLogValue() const { return str_tmp; } -double STT::CalAngleVect_rad(const Vector<3>& vect1, const Vector<3>& vect2) { - Vector<3> vect1_normal(vect1); +double STT::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector2) { + Vector<3> vect1_normal(vector1); Normalize(vect1_normal); // Normalize Vector1 - Vector<3> vect2_normal(vect2); + Vector<3> vect2_normal(vector2); Normalize(vect2_normal); // Normalize Vector2 double cosTheta = InnerProduct(vect1_normal, vect2_normal); // Calc cos value double theta_rad = acos(cosTheta); diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 1fe7b10e0..1f8f9c980 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -140,25 +140,25 @@ class STT : public Component, public ILoggable { /** * @fn update * @brief Update delay buffer - * @param [in] local_celes_info: Local celestial information - * @param [in] attinfo: Attitude information + * @param [in] local_celestial_information: Local celestial information + * @param [in] attitude: Attitude information */ - void update(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo); + void update(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); /** * @fn measure * @brief Calculate measured quaternion - * @param [in] local_celes_info: Local celestial information - * @param [in] attinfo: Attitude information + * @param [in] local_celestial_information: Local celestial information + * @param [in] attitude: Attitude information */ - libra::Quaternion measure(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo); + libra::Quaternion measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); /** * @fn AllJudgement * @brief Calculate all error judgement - * @param [in] local_celes_info: Local celestial information - * @param [in] attinfo: Attitude information + * @param [in] local_celestial_information: Local celestial information + * @param [in] attitude: Attitude information */ - void AllJudgement(const LocalCelestialInformation* local_celes_info, const Attitude* attinfo); + void AllJudgement(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); /** * @fn SunJudgement * @brief Judge violation of sun forbidden angle @@ -183,18 +183,18 @@ class STT : public Component, public ILoggable { /** * @fn CaptureRateJudgement * @brief Judge violation of angular velocity limit - * @param [in] omega_b: Angular velocity of spacecraft in the body fixed frame + * @param [in] omega_b_rad_s: Angular velocity of spacecraft in the body fixed frame * @return 1: violated, 0: not violated */ - int CaptureRateJudgement(const libra::Vector<3>& omega_b); + int CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s); /** - * @fn CalAngleVect_rad + * @fn CalAngleVector_rad * @brief Calculate angle between two vectors - * @param [in] vect1: First vector - * @param [in] vect2: Second vector + * @param [in] vector1: First vector + * @param [in] vector2: Second vector * @return Angle between two vectors [rad] */ - double CalAngleVect_rad(const libra::Vector<3>& vect1, const libra::Vector<3>& vect2); + double CalAngleVector_rad(const libra::Vector<3>& vector1, const libra::Vector<3>& vector2); /** * @fn Initialize diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 3ac1ed201..66a40207c 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -16,28 +16,28 @@ using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info) + const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), - local_celes_info_(local_celes_info) { + local_celes_info_(local_celestial_information) { Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info) + const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), - local_celes_info_(local_celes_info) { + local_celes_info_(local_celestial_information) { Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 5a7de89bb..5f66cfcdc 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -33,12 +33,12 @@ class SunSensor : public Component, public ILoggable { * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info); + const LocalCelestialInformation* local_celestial_information); /** * @fn SunSensor * @brief Constructor with power port @@ -52,12 +52,12 @@ class SunSensor : public Component, public ILoggable { * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info); + const LocalCelestialInformation* local_celestial_information); // Override functions for Component /** diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index 022918502..8f80772a0 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -14,7 +14,7 @@ using namespace std; Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info) { + const LocalCelestialInformation* local_celestial_information) { using libra::pi; IniAccess Telescope_conf(fname); @@ -49,6 +49,6 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); Telescope telescope(clock_generator, quaternion_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, - y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celes_info); + y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celestial_information); return telescope; } diff --git a/src/components/real/mission/initialize_telescope.hpp b/src/components/real/mission/initialize_telescope.hpp index b67694904..898fc3aff 100644 --- a/src/components/real/mission/initialize_telescope.hpp +++ b/src/components/real/mission/initialize_telescope.hpp @@ -16,9 +16,9 @@ * @param [in] fname: Path to initialize file * @param [in] attitude: Attitude information * @param [in] hipp: Star information by Hipparcos catalogue - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information */ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const Attitude* attitude, - const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); + const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 51567958a..771bd9045 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -14,7 +14,7 @@ using namespace libra; Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celes_info) + const LocalCelestialInformation* local_celestial_information) : Component(1, clock_generator), quaternion_b2c_(quaternion_b2c), sun_forbidden_angle_rad_(sun_forbidden_angle), @@ -27,7 +27,7 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern num_of_logged_stars_(num_of_logged_stars), attitude_(attitude), hipp_(hipp), - local_celes_info_(local_celes_info) { + local_celes_info_(local_celestial_information) { is_sun_in_forbidden_angle = true; is_earth_in_forbidden_angle = true; is_moon_in_forbidden_angle = true; diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 2d43bd823..bd6d97f9c 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -32,7 +32,7 @@ class Telescope : public Component, public ILoggable { public: Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, - const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celes_info); + const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information); ~Telescope(); diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index d72694312..66c59f739 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info, double compo_step_time) { + const LocalCelestialInformation* local_celestial_information, double compo_step_time) { IniAccess sap_conf(fname); const std::string st_sap_id = std::to_string(sap_id); @@ -41,7 +41,7 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, - transmission_efficiency, srp, local_celes_info, compo_step_time); + transmission_efficiency, srp, local_celestial_information, compo_step_time); return sap; } diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index ff3bba712..cfc8f7992 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -15,11 +15,11 @@ * @param [in] sap_id: SAP ID * @param [in] fname: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info, double compo_step_time); + const LocalCelestialInformation* local_celestial_information, double compo_step_time); /* * @fn InitSAP diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 65b00826a..3189933c6 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -10,7 +10,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info, double compo_step_time) + const LocalCelestialInformation* local_celestial_information, double compo_step_time) : Component(prescaler, clock_generator), component_id_(component_id), number_of_series_(number_of_series), @@ -20,7 +20,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - local_celes_info_(local_celes_info), + local_celes_info_(local_celestial_information), compo_step_time_(compo_step_time) { voltage_ = 0.0; power_generation_ = 0.0; @@ -45,7 +45,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info) + const LocalCelestialInformation* local_celestial_information) : Component(10, clock_generator), component_id_(component_id), number_of_series_(number_of_series), @@ -55,7 +55,7 @@ SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - local_celes_info_(local_celes_info), + local_celes_info_(local_celestial_information), compo_step_time_(0.1) { voltage_ = 0.0; power_generation_ = 0.0; diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 9090e8846..b5329762a 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -28,12 +28,12 @@ class SAP : public Component, public ILoggable { * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU * @param [in] srp: Solar Radiation Pressure environment - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info, double compo_step_time); + const LocalCelestialInformation* local_celestial_information, double compo_step_time); /** * @fn SAP * @brief Constructor with prescaler @@ -65,11 +65,11 @@ class SAP : public Component, public ILoggable { * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU * @param [in] srp: Solar Radiation Pressure environment - * @param [in] local_celes_info: Local celestial information + * @param [in] local_celestial_information: Local celestial information */ SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celes_info); + const LocalCelestialInformation* local_celestial_information); /** * @fn SAP * @brief Copy constructor From 8c3fc1ca38673bdee6763fda736979d8a110e05f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:32:25 +0100 Subject: [PATCH 0817/1086] Fix public function name --- src/components/real/aocs/star_sensor.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 1f8f9c980..833398d73 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -92,10 +92,10 @@ class STT : public Component, public ILoggable { virtual std::string GetLogValue() const; /** - * @fn GetObsQuaternion + * @fn GetMeasuredQuaternion_i2c * @brief Return observed quaternion from the inertial frame to the component frame */ - inline const libra::Quaternion GetObsQuaternion() const { return measured_quaternion_i2c_; }; + inline const libra::Quaternion GetMeasuredQuaternion_i2c() const { return measured_quaternion_i2c_; }; /** * @fn GetErrorFlag * @brief Return error flag From 256c8402263402c6de8c085144cf2c4835419450 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:34:54 +0100 Subject: [PATCH 0818/1086] Fix function arguments --- .../real/aocs/initialize_star_sensor.cpp | 34 ++++++------- .../real/aocs/initialize_star_sensor.hpp | 8 ++-- .../real/aocs/initialize_sun_sensor.hpp | 4 +- src/components/real/aocs/star_sensor.cpp | 46 +++++++++--------- src/components/real/aocs/star_sensor.hpp | 48 ++++++++++--------- src/components/real/mission/telescope.cpp | 12 ++--- src/components/real/mission/telescope.hpp | 7 +-- .../solar_radiation_pressure_disturbance.cpp | 6 +-- .../solar_radiation_pressure_disturbance.hpp | 2 +- .../sample_spacecraft/sample_components.cpp | 4 +- .../sample_spacecraft/sample_components.hpp | 2 +- 11 files changed, 90 insertions(+), 83 deletions(-) diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index 206b7fd29..8438e4d07 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -11,7 +11,7 @@ using namespace std; STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_env) { + const LocalEnvironment* local_environment) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -19,15 +19,15 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - double step_time = compo_step_time * prescaler; + double step_time_s = compo_step_time * prescaler; Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); - double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); - double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); + double standard_deviation_orthogonal_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); + double standard_deviation_sight_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); - int output_delay = max(int(output_delay_sec / step_time), 1); + int output_delay = max(int(output_delay_sec / step_time_s), 1); double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); - int output_interval = max(int(output_interval_sec / step_time), 1); + int output_interval = max(int(output_interval_sec / step_time_s), 1); double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_exclusion_angle_deg"); @@ -37,13 +37,14 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; - STT stt(prescaler, clock_generator, sensor_id, quaternion_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, - sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); + STT stt(prescaler, clock_generator, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, standard_deviation_sight_direction, + step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, + capture_rate_rad_s, dynamics, local_environment); return stt; } STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, - const Dynamics* dynamics, const LocalEnvironment* local_env) { + const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -51,16 +52,16 @@ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_i int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - double step_time = compo_step_time * prescaler; + double step_time_s = compo_step_time * prescaler; Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); - double sigma_ortho = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); - double sigma_sight = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); + double standard_deviation_orthogonal_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); + double standard_deviation_sight_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); double output_delay_sec = STT_conf.ReadDouble(STTSection, "output_delay_s"); - int output_delay = max(int(output_delay_sec / step_time), 1); + int output_delay = max(int(output_delay_sec / step_time_s), 1); double output_interval_sec = STT_conf.ReadDouble(STTSection, "output_interval_s"); - int output_interval = max(int(output_interval_sec / step_time), 1); + int output_interval = max(int(output_interval_sec / step_time_s), 1); double sun_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "sun_exclusion_angle_deg"); double sun_forbidden_angle_rad = sun_forbidden_angle_deg * libra::pi / 180.0; double earth_forbidden_angle_deg = STT_conf.ReadDouble(STTSection, "earth_exclusion_angle_deg"); @@ -72,7 +73,8 @@ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_i power_port->InitializeWithInitializeFile(fname); - STT stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, sigma_ortho, sigma_sight, step_time, output_delay, output_interval, - sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_env); + STT stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, + standard_deviation_sight_direction, step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, + moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_environment); return stt; } diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index 067b8a0e3..9211c4044 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -16,10 +16,10 @@ * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] dynamics: Dynamics information - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_env); + const LocalEnvironment* local_environment); /** * @fn InitSTT * @brief Initialize functions for STT with power port @@ -29,9 +29,9 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fn * @param [in] fname: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] dynamics: Dynamics information - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const Dynamics* dynamics, const LocalEnvironment* local_env); + const Dynamics* dynamics, const LocalEnvironment* local_environment); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index 4da7194f1..688282b3f 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -15,7 +15,7 @@ * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] srp: Solar radiation pressure environment - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); @@ -27,7 +27,7 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file * @param [in] srp: Solar radiation pressure environment - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index b1533d5e5..93a6d16ec 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -16,49 +16,51 @@ using namespace std; using namespace libra; STT::STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, - const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, - const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, + const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), rotation_noise_(global_randomization.MakeSeed()), - orthogonal_direction_noise_(0.0, sigma_ortho, global_randomization.MakeSeed()), - sight_direction_noise_(0.0, sigma_sight, global_randomization.MakeSeed()), + orthogonal_direction_noise_(0.0, standard_deviation_orthogonal_direction, global_randomization.MakeSeed()), + sight_direction_noise_(0.0, standard_deviation_sight_direction, global_randomization.MakeSeed()), buffer_position_(0), - step_time_s_(step_time), + step_time_s_(step_time_s), output_delay_(output_delay), output_interval_(output_interval), update_count_(0), - sun_forbidden_angle_rad_(sun_forbidden_angle), - earth_forbidden_angle_rad_(earth_forbidden_angle), - moon_forbidden_angle_rad_(moon_forbidden_angle), - capture_rate_limit_rad_s_(capture_rate), + sun_forbidden_angle_rad_(sun_forbidden_angle_rad), + earth_forbidden_angle_rad_(earth_forbidden_angle_rad), + moon_forbidden_angle_rad_(moon_forbidden_angle_rad), + capture_rate_limit_rad_s_(capture_rate_limit_rad_s), dynamics_(dynamics), - local_environment_(local_env) { + local_environment_(local_environment) { Initialize(); } STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, - const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, - const unsigned int output_interval, const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, - const double capture_rate, const Dynamics* dynamics, const LocalEnvironment* local_env) + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, + const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), rotation_noise_(global_randomization.MakeSeed()), - orthogonal_direction_noise_(0.0, sigma_ortho, global_randomization.MakeSeed()), - sight_direction_noise_(0.0, sigma_sight, global_randomization.MakeSeed()), + orthogonal_direction_noise_(0.0, standard_deviation_orthogonal_direction, global_randomization.MakeSeed()), + sight_direction_noise_(0.0, standard_deviation_sight_direction, global_randomization.MakeSeed()), buffer_position_(0), - step_time_s_(step_time), + step_time_s_(step_time_s), output_delay_(output_delay), output_interval_(output_interval), update_count_(0), - sun_forbidden_angle_rad_(sun_forbidden_angle), - earth_forbidden_angle_rad_(earth_forbidden_angle), - moon_forbidden_angle_rad_(moon_forbidden_angle), - capture_rate_limit_rad_s_(capture_rate), + sun_forbidden_angle_rad_(sun_forbidden_angle_rad), + earth_forbidden_angle_rad_(earth_forbidden_angle_rad), + moon_forbidden_angle_rad_(moon_forbidden_angle_rad), + capture_rate_limit_rad_s_(capture_rate_limit_rad_s), dynamics_(dynamics), - local_environment_(local_env) { + local_environment_(local_environment) { Initialize(); } diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 833398d73..77cd9faec 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -31,22 +31,23 @@ class STT : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] - * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] - * @param [in] step_time: Step time for delay calculation [sec] + * @param [in] standard_deviation_orthogonal_direction: Standard deviation for random noise in orthogonal direction of sight [rad] + * @param [in] standard_deviation_sight_direction: Standard deviation for random noise in sight direction[rad] + * @param [in] step_time_s: Step time for delay calculation [sec] * @param [in] output_delay: Output delay [0, max_delay_] [step_sec] * @param [in] output_interval: Output interval [step_sec] - * @param [in] sun_forbidden_angle: Sun forbidden angle [rad] - * @param [in] earth_forbidden_angle: Earth forbidden angle [rad] - * @param [in] moon_forbidden_angle: Moon forbidden angle [rad] - * @param [in] capture_rate: Angular rate limit to get correct attitude [rad/s] + * @param [in] sun_forbidden_angle_rad: Sun forbidden angle [rad] + * @param [in] earth_forbidden_angle_rad: Earth forbidden angle [rad] + * @param [in] moon_forbidden_angle_rad: Moon forbidden angle [rad] + * @param [in] capture_rate_limit_rad_s: Angular rate limit to get correct attitude [rad/s] * @param [in] dynamics: Dynamics information - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double sigma_ortho, - const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, - const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, - const Dynamics* dynamics, const LocalEnvironment* local_env); + STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, + const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, + const LocalEnvironment* local_environment); /** * @fn STT * @brief Constructor with power port @@ -55,22 +56,23 @@ class STT : public Component, public ILoggable { * @param [in] power_port: Power port * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame - * @param [in] sigma_ortho: Standard deviation for random noise in orthogonal direction of sight [rad] - * @param [in] sigma_sight: Standard deviation for random noise in sight direction[rad] - * @param [in] step_time: Step time for delay calculation [sec] + * @param [in] standard_deviation_orthogonal_direction: Standard deviation for random noise in orthogonal direction of sight [rad] + * @param [in] standard_deviation_sight_direction: Standard deviation for random noise in sight direction[rad] + * @param [in] step_time_s: Step time for delay calculation [sec] * @param [in] output_delay: Output delay [0, max_delay_] [step_sec] * @param [in] output_interval: Output interval [step_sec] - * @param [in] sun_forbidden_angle: Sun forbidden angle [rad] - * @param [in] earth_forbidden_angle: Earth forbidden angle [rad] - * @param [in] moon_forbidden_angle: Moon forbidden angle [rad] - * @param [in] capture_rate: Angular rate limit to get correct attitude [rad/s] + * @param [in] sun_forbidden_angle_rad: Sun forbidden angle [rad] + * @param [in] earth_forbidden_angle_rad: Earth forbidden angle [rad] + * @param [in] moon_forbidden_angle_rad: Moon forbidden angle [rad] + * @param [in] capture_rate_limit_rad_s: Angular rate limit to get correct attitude [rad/s] * @param [in] dynamics: Dynamics information - * @param [in] local_env: Local environment information + * @param [in] local_environment: Local environment information */ STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, - const double sigma_ortho, const double sigma_sight, const double step_time, const unsigned int output_delay, const unsigned int output_interval, - const double sun_forbidden_angle, const double earth_forbidden_angle, const double moon_forbidden_angle, const double capture_rate, - const Dynamics* dynamics, const LocalEnvironment* local_env); + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, + const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, + const LocalEnvironment* local_environment); // Override functions for Component /** diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 771bd9045..29c9fe082 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -11,15 +11,15 @@ using namespace std; using namespace libra; -Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, - double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, - size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, +Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle_rad, + double earth_forbidden_angle_rad, double moon_forbidden_angle_rad, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, + double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information) : Component(1, clock_generator), quaternion_b2c_(quaternion_b2c), - sun_forbidden_angle_rad_(sun_forbidden_angle), - earth_forbidden_angle_rad_(earth_forbidden_angle), - moon_forbidden_angle_rad_(moon_forbidden_angle), + sun_forbidden_angle_rad_(sun_forbidden_angle_rad), + earth_forbidden_angle_rad_(earth_forbidden_angle_rad), + moon_forbidden_angle_rad_(moon_forbidden_angle_rad), x_num_of_pix_(x_num_of_pix), y_num_of_pix_(y_num_of_pix), x_fov_par_pix_(x_fov_par_pix), diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index bd6d97f9c..0d4e030ba 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -30,9 +30,10 @@ struct Star { */ class Telescope : public Component, public ILoggable { public: - Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle, double earth_forbidden_angle, - double moon_forbidden_angle, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, size_t num_of_logged_stars, - const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information); + Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle_rad, double earth_forbidden_angle_rad, + double moon_forbidden_angle_rad, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, + size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, + const LocalCelestialInformation* local_celestial_information); ~Telescope(); diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 808ddeb5c..29980dccb 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -13,11 +13,11 @@ SolarRadiationPressureDisturbance::SolarRadiationPressureDisturbance(const vecto const bool is_calculation_enabled) : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) {} -void SolarRadiationPressureDisturbance::Update(const LocalEnvironment& local_env, const Dynamics& dynamics) { +void SolarRadiationPressureDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { UNUSED(dynamics); - libra::Vector<3> sun_position_from_sc_b_m = local_env.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); - CalcTorqueForce(sun_position_from_sc_b_m, local_env.GetSolarRadiationPressure().GetPressure_N_m2()); + libra::Vector<3> sun_position_from_sc_b_m = local_environment.GetCelestialInformation().GetPositionFromSpacecraft_b_m("SUN"); + CalcTorqueForce(sun_position_from_sc_b_m, local_environment.GetSolarRadiationPressure().GetPressure_N_m2()); } void SolarRadiationPressureDisturbance::CalcCoefficients(const libra::Vector<3>& input_direction_b, const double item) { diff --git a/src/disturbances/solar_radiation_pressure_disturbance.hpp b/src/disturbances/solar_radiation_pressure_disturbance.hpp index 9f5e65427..34414bdf1 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.hpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.hpp @@ -34,7 +34,7 @@ class SolarRadiationPressureDisturbance : public SurfaceForce { * @param [in] local_environment: Local environment information * @param [in] dynamics: Dynamics information */ - virtual void Update(const LocalEnvironment& local_env, const Dynamics& dynamics); + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics); // Override ILoggable /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index d1fde030f..d81887fce 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -9,9 +9,9 @@ #include "sample_port_configuration.hpp" -SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_env, +SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id) - : config_(config), dynamics_(dynamics), structure_(structure), local_env_(local_env), glo_env_(glo_env) { + : config_(config), dynamics_(dynamics), structure_(structure), local_env_(local_environment), glo_env_(glo_env) { IniAccess iniAccess = IniAccess(config_->sat_file_[sat_id]); // PCU power port connection diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 063ef505a..f0ca23a3f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -53,7 +53,7 @@ class SampleComponents : public InstalledComponents { * @fn SampleComponents * @brief Constructor */ - SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_env, const GlobalEnvironment* glo_env, + SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id); /** * @fn ~SampleComponents From 33352634d53c5d3aa061a77209f33436e475fd6f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:35:29 +0100 Subject: [PATCH 0819/1086] Rename STT to StarSensor --- .../real/aocs/initialize_star_sensor.cpp | 20 ++++---- .../real/aocs/initialize_star_sensor.hpp | 12 ++--- src/components/real/aocs/star_sensor.cpp | 47 ++++++++++--------- src/components/real/aocs/star_sensor.hpp | 33 ++++++------- .../sample_spacecraft/sample_components.cpp | 6 +-- .../sample_spacecraft/sample_components.hpp | 4 +- 6 files changed, 62 insertions(+), 60 deletions(-) diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index 8438e4d07..ad1d32ed2 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -10,8 +10,8 @@ using namespace std; -STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_environment) { +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, + const LocalEnvironment* local_environment) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -37,14 +37,14 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; - STT stt(prescaler, clock_generator, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, standard_deviation_sight_direction, - step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, - capture_rate_rad_s, dynamics, local_environment); + StarSensor stt(prescaler, clock_generator, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, standard_deviation_sight_direction, + step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, + capture_rate_rad_s, dynamics, local_environment); return stt; } -STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, - const Dynamics* dynamics, const LocalEnvironment* local_environment) { +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, + const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(fname); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -73,8 +73,8 @@ STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_i power_port->InitializeWithInitializeFile(fname); - STT stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, - standard_deviation_sight_direction, step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, - moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_environment); + StarSensor stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, + standard_deviation_sight_direction, step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, + moon_forbidden_angle_rad, capture_rate_rad_s, dynamics, local_environment); return stt; } diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index 9211c4044..c3e0ee902 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -10,7 +10,7 @@ /** * @fn InitSTT - * @brief Initialize functions for STT without power port + * @brief Initialize functions for StarSensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] fname: Path to the initialize file @@ -18,11 +18,11 @@ * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_environment); +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, + const LocalEnvironment* local_environment); /** * @fn InitSTT - * @brief Initialize functions for STT with power port + * @brief Initialize functions for StarSensor with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID @@ -31,7 +31,7 @@ STT InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fn * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -STT InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, - const Dynamics* dynamics, const LocalEnvironment* local_environment); +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, + const Dynamics* dynamics, const LocalEnvironment* local_environment); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 93a6d16ec..e2cabe7bf 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -15,11 +15,11 @@ using namespace std; using namespace libra; -STT::STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, - const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, - const Dynamics* dynamics, const LocalEnvironment* local_environment) +StarSensor::StarSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, + const double step_time_s, const unsigned int output_delay, const unsigned int output_interval, + const double sun_forbidden_angle_rad, const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, + const double capture_rate_limit_rad_s, const Dynamics* dynamics, const LocalEnvironment* local_environment) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -39,11 +39,12 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, const int compone local_environment_(local_environment) { Initialize(); } -STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, - const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, - const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, - const Dynamics* dynamics, const LocalEnvironment* local_environment) +StarSensor::StarSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const libra::Quaternion& quaternion_b2c, const double standard_deviation_orthogonal_direction, + const double standard_deviation_sight_direction, const double step_time_s, const unsigned int output_delay, + const unsigned int output_interval, const double sun_forbidden_angle_rad, const double earth_forbidden_angle_rad, + const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, + const LocalEnvironment* local_environment) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -64,7 +65,7 @@ STT::STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_ Initialize(); } -void STT::Initialize() { +void StarSensor::Initialize() { measured_quaternion_i2c_ = Quaternion(0.0, 0.0, 0.0, 1.0); // Decide delay buffer size @@ -86,7 +87,7 @@ void STT::Initialize() { error_flag_ = true; } -Quaternion STT::measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { +Quaternion StarSensor::measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { update(local_celestial_information, attitude); // update delay buffer if (update_count_ == 0) { int hist = buffer_position_ - output_delay_ - 1; @@ -102,7 +103,7 @@ Quaternion STT::measure(const LocalCelestialInformation* local_celestial_informa return measured_quaternion_i2c_; } -void STT::update(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { +void StarSensor::update(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { Quaternion quaternion_i2b = attitude->GetQuaternion_i2b(); // Read true value Quaternion q_stt_temp = quaternion_i2b * quaternion_b2c_; // Convert to component frame // Add noise on sight direction @@ -115,7 +116,7 @@ void STT::update(const LocalCelestialInformation* local_celestial_information, c // Judge errors AllJudgement(local_celestial_information, attitude); - // Calc observed quaternion: Inertial frame → STT frame → Rotation around + // Calc observed quaternion: Inertial frame → StarSensor frame → Rotation around // sight →Rotation around orthogonal direction delay_buffer_[buffer_position_] = q_stt_temp * q_sight * q_ortho; // Update delay buffer position @@ -123,7 +124,7 @@ void STT::update(const LocalCelestialInformation* local_celestial_information, c buffer_position_ %= max_delay_; } -void STT::AllJudgement(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { +void StarSensor::AllJudgement(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { int judgement = 0; judgement = SunJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("SUN")); judgement += EarthJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("EARTH")); @@ -135,7 +136,7 @@ void STT::AllJudgement(const LocalCelestialInformation* local_celestial_informat error_flag_ = false; } -int STT::SunJudgement(const libra::Vector<3>& sun_b) { +int StarSensor::SunJudgement(const libra::Vector<3>& sun_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double sun_angle_rad = CalAngleVector_rad(sun_b, sight_b); @@ -145,7 +146,7 @@ int STT::SunJudgement(const libra::Vector<3>& sun_b) { return 0; } -int STT::EarthJudgement(const libra::Vector<3>& earth_b) { +int StarSensor::EarthJudgement(const libra::Vector<3>& earth_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, @@ -158,7 +159,7 @@ int STT::EarthJudgement(const libra::Vector<3>& earth_b) { return 0; } -int STT::MoonJudgement(const libra::Vector<3>& moon_b) { +int StarSensor::MoonJudgement(const libra::Vector<3>& moon_b) { Quaternion q_c2b = quaternion_b2c_.Conjugate(); Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double moon_angle_rad = CalAngleVector_rad(moon_b, sight_b); @@ -168,7 +169,7 @@ int STT::MoonJudgement(const libra::Vector<3>& moon_b) { return 0; } -int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s) { +int StarSensor::CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s) { double omega_norm = CalcNorm(omega_b_rad_s); if (omega_norm > capture_rate_limit_rad_s_) return 1; @@ -176,7 +177,7 @@ int STT::CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s) { return 0; } -std::string STT::GetLogHeader() const { +std::string StarSensor::GetLogHeader() const { std::string str_tmp = ""; const std::string sensor_id = std::to_string(static_cast(component_id_)); std::string sensor_name = "stt" + sensor_id + "_"; @@ -187,7 +188,7 @@ std::string STT::GetLogHeader() const { return str_tmp; } -std::string STT::GetLogValue() const { +std::string StarSensor::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteQuaternion(measured_quaternion_i2c_); @@ -196,7 +197,7 @@ std::string STT::GetLogValue() const { return str_tmp; } -double STT::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector2) { +double StarSensor::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector2) { Vector<3> vect1_normal(vector1); Normalize(vect1_normal); // Normalize Vector1 Vector<3> vect2_normal(vector2); @@ -206,7 +207,7 @@ double STT::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector return theta_rad; } -void STT::MainRoutine(int count) { +void StarSensor::MainRoutine(int count) { UNUSED(count); measure(&(local_environment_->GetCelestialInformation()), &(dynamics_->GetAttitude())); diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 77cd9faec..91d0e5e04 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -19,13 +19,13 @@ #include "dynamics/dynamics.hpp" /* - * @class STT + * @class StarSensor * @brief Class to emulate star tracker */ -class STT : public Component, public ILoggable { +class StarSensor : public Component, public ILoggable { public: /** - * @fn STT + * @fn StarSensor * @brief Constructor without power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -43,13 +43,13 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, - const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, - const LocalEnvironment* local_environment); + StarSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, + const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, + const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment); /** - * @fn STT + * @fn StarSensor * @brief Constructor with power port * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -68,11 +68,12 @@ class STT : public Component, public ILoggable { * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ - STT(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, - const double standard_deviation_orthogonal_direction, const double standard_deviation_sight_direction, const double step_time_s, - const unsigned int output_delay, const unsigned int output_interval, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, - const LocalEnvironment* local_environment); + StarSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const libra::Quaternion& quaternion_b2c, const double standard_deviation_orthogonal_direction, + const double standard_deviation_sight_direction, const double step_time_s, const unsigned int output_delay, + const unsigned int output_interval, const double sun_forbidden_angle_rad, const double earth_forbidden_angle_rad, + const double moon_forbidden_angle_rad, const double capture_rate_limit_rad_s, const Dynamics* dynamics, + const LocalEnvironment* local_environment); // Override functions for Component /** @@ -105,10 +106,10 @@ class STT : public Component, public ILoggable { inline bool GetErrorFlag() const { return error_flag_; } protected: - // STT general parameters + // StarSensor general parameters const int component_id_; //!< Sensor ID libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame - libra::Quaternion measured_quaternion_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< STT observed quaternion + libra::Quaternion measured_quaternion_i2c_ = {0.0, 0.0, 0.0, 1.0}; //!< StarSensor observed quaternion libra::Vector<3> sight_direction_c_; //!< Sight direction vector at component frame libra::Vector<3> first_orthogonal_direction_c; //!< The first orthogonal direction of sight at component frame libra::Vector<3> second_orthogonal_direction_c; //!< The second orthogonal direction of sight at component frame diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index d81887fce..da150c704 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -35,11 +35,11 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur mag_sensor_ = new Magnetometer(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); - // STT + // StarSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - stt_ = - new STT(InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); + stt_ = new StarSensor( + InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index f0ca23a3f..2a9b8718e 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -34,7 +34,7 @@ class OBC; class PCU; class GyroSensor; class Magnetometer; -class STT; +class StarSensor; class SunSensor; class GnssReceiver; class Magnetorquer; @@ -89,7 +89,7 @@ class SampleComponents : public InstalledComponents { // AOCS GyroSensor* gyro_; //!< GyroSensor sensor Magnetometer* mag_sensor_; //!< Magnetmeter - STT* stt_; //!< Star sensor + StarSensor* stt_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor GnssReceiver* gnss_; //!< GNSS receiver Magnetorquer* mag_torquer_; //!< Magnetorquer From 538ab8443eedf7689402805874c61074c42c9a7d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:36:47 +0100 Subject: [PATCH 0820/1086] Fix function arguments --- src/components/real/aocs/star_sensor.cpp | 4 ++-- src/components/real/aocs/star_sensor.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index e2cabe7bf..a2b6808b1 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -207,8 +207,8 @@ double StarSensor::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& return theta_rad; } -void StarSensor::MainRoutine(int count) { - UNUSED(count); +void StarSensor::MainRoutine(const int time_count) { + UNUSED(time_count); measure(&(local_environment_->GetCelestialInformation()), &(dynamics_->GetAttitude())); } diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 91d0e5e04..90be051ea 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -80,7 +80,7 @@ class StarSensor : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** From 9d80db904075a7967ff6008190a59d3012086c66 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:40:35 +0100 Subject: [PATCH 0821/1086] Fix private variables name --- src/components/real/aocs/sun_sensor.cpp | 58 +++++++++---------- src/components/real/aocs/sun_sensor.hpp | 36 ++++++------ src/components/real/mission/telescope.cpp | 14 ++--- src/components/real/mission/telescope.hpp | 6 +- .../real/power/solar_array_panel.cpp | 8 +-- .../real/power/solar_array_panel.hpp | 4 +- src/dynamics/thermal/node.cpp | 6 +- src/dynamics/thermal/node.hpp | 2 +- 8 files changed, 67 insertions(+), 67 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 66a40207c..54b1b7eb3 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -23,7 +23,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), - local_celes_info_(local_celestial_information) { + local_celestial_information_(local_celestial_information) { Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } @@ -37,19 +37,19 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), srp_(srp), - local_celes_info_(local_celestial_information) { + local_celestial_information_(local_celestial_information) { Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); } void SunSensor::Initialize(const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c) { // Bias NormalRand nr(0.0, nr_bias_stddev_c, global_randomization.MakeSeed()); - bias_alpha_ += nr; - bias_beta_ += nr; + bias_noise_alpha_rad_ += nr; + bias_noise_beta_rad_ += nr; // Normal Random - nrs_alpha_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() - nrs_beta_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() + random_noise_alpha_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() + random_noise_beta_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() } void SunSensor::MainRoutine(int count) { UNUSED(count); @@ -58,48 +58,48 @@ void SunSensor::MainRoutine(int count) { } void SunSensor::measure() { - libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); + libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = Normalize(sun_pos_b); - sun_c_ = quaternion_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component + sun_direction_true_c_ = quaternion_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component SunDetectionJudgement(); // Judge the sun is inside the FoV if (sun_detected_flag_) { - alpha_ = atan2(sun_c_[0], sun_c_[2]); - beta_ = atan2(sun_c_[1], sun_c_[2]); + alpha_rad_ = atan2(sun_direction_true_c_[0], sun_direction_true_c_[2]); + beta_rad_ = atan2(sun_direction_true_c_[1], sun_direction_true_c_[2]); // Add constant bias noise - alpha_ += bias_alpha_; - beta_ += bias_beta_; + alpha_rad_ += bias_noise_alpha_rad_; + beta_rad_ += bias_noise_beta_rad_; // Add Normal random noise - alpha_ += nrs_alpha_; - beta_ += nrs_beta_; + alpha_rad_ += random_noise_alpha_; + beta_rad_ += random_noise_beta_; // Range [-π/2:π/2] - alpha_ = TanRange(alpha_); - beta_ = TanRange(beta_); + alpha_rad_ = TanRange(alpha_rad_); + beta_rad_ = TanRange(beta_rad_); - measured_sun_c_[0] = tan(alpha_); - measured_sun_c_[1] = tan(beta_); - measured_sun_c_[2] = 1.0; + measured_sun_direction_c_[0] = tan(alpha_rad_); + measured_sun_direction_c_[1] = tan(beta_rad_); + measured_sun_direction_c_[2] = 1.0; - measured_sun_c_ = Normalize(measured_sun_c_); + measured_sun_direction_c_ = Normalize(measured_sun_direction_c_); } else { - measured_sun_c_ = libra::Vector<3>(0); - alpha_ = 0.0; - beta_ = 0.0; + measured_sun_direction_c_ = libra::Vector<3>(0); + alpha_rad_ = 0.0; + beta_rad_ = 0.0; } CalcSolarIlluminance(); } void SunSensor::SunDetectionJudgement() { - libra::Vector<3> sun_direction_c = Normalize(sun_c_); + libra::Vector<3> sun_direction_c = Normalize(sun_direction_true_c_); double sun_angle_ = acos(sun_direction_c[2]); - if (solar_illuminance_ < intensity_lower_threshold_percent_ / 100.0 * srp_->GetSolarConstant_W_m2()) { + if (solar_illuminance_W_m2_ < intensity_lower_threshold_percent_ / 100.0 * srp_->GetSolarConstant_W_m2()) { sun_detected_flag_ = false; } else { if (sun_angle_ < detectable_angle_rad_) { @@ -111,16 +111,16 @@ void SunSensor::SunDetectionJudgement() { } void SunSensor::CalcSolarIlluminance() { - libra::Vector<3> sun_direction_c = Normalize(sun_c_); + libra::Vector<3> sun_direction_c = Normalize(sun_direction_true_c_); double sun_angle_ = acos(sun_direction_c[2]); if (sun_angle_ > libra::pi_2) { - solar_illuminance_ = 0.0; + solar_illuminance_W_m2_ = 0.0; return; } double power_density = srp_->GetPowerDensity_W_m2(); - solar_illuminance_ = power_density * cos(sun_angle_); + solar_illuminance_W_m2_ = power_density * cos(sun_angle_); // TODO: Take into account the effects of albedo. } @@ -144,7 +144,7 @@ string SunSensor::GetLogHeader() const { string SunSensor::GetLogValue() const { string str_tmp = ""; - str_tmp += WriteVector(measured_sun_c_); + str_tmp += WriteVector(measured_sun_direction_c_); str_tmp += WriteScalar(double(sun_detected_flag_)); return str_tmp; diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 5f66cfcdc..603f6aa36 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -80,34 +80,34 @@ class SunSensor : public Component, public ILoggable { // Getter inline bool GetSunDetectedFlag() const { return sun_detected_flag_; }; - inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_c_; }; - inline const libra::Vector<3> GetMeasuredSun_b() const { return quaternion_b2c_.Conjugate().FrameConversion(measured_sun_c_); }; - inline double GetSunAngleAlpha() const { return alpha_; }; - inline double GetSunAngleBeta() const { return beta_; }; - inline double GetSolarIlluminance() const { return solar_illuminance_; }; + inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_direction_c_; }; + inline const libra::Vector<3> GetMeasuredSun_b() const { return quaternion_b2c_.Conjugate().FrameConversion(measured_sun_direction_c_); }; + inline double GetSunAngleAlpha() const { return alpha_rad_; }; + inline double GetSunAngleBeta() const { return beta_rad_; }; + inline double GetSolarIlluminance() const { return solar_illuminance_W_m2_; }; protected: const int component_id_; //!< Sensor ID libra::Quaternion quaternion_b2c_; //!< Quaternion from body frame to component frame (Z-axis of the component is sight direction) double intensity_lower_threshold_percent_; //!< If the light intensity becomes smaller than this, it becomes impossible to get the sun direction - libra::Vector<3> sun_c_{0.0}; //!< True value of sun vector in the component frame - libra::Vector<3> measured_sun_c_{0.0}; //!< Measured sun vector in the component frame + libra::Vector<3> sun_direction_true_c_{0.0}; //!< True value of sun vector in the component frame + libra::Vector<3> measured_sun_direction_c_{0.0}; //!< Measured sun vector in the component frame - double alpha_ = 0.0; //!< Angle between Z-axis and the sun direction projected on XZ plane [rad] - double beta_ = 0.0; //!< Angle between Z-axis and the sun direction projected on YZ plane [rad] - double solar_illuminance_ = 0.0; //!< The energy of sunlight per unit area, taking into account the angle to the sun [W/m^2] - double detectable_angle_rad_; //!< half angle (>0) [rad] - bool sun_detected_flag_ = false; //!< Sun detected flag + double alpha_rad_ = 0.0; //!< Angle between Z-axis and the sun direction projected on XZ plane [rad] + double beta_rad_ = 0.0; //!< Angle between Z-axis and the sun direction projected on YZ plane [rad] + double solar_illuminance_W_m2_ = 0.0; //!< The energy of sunlight per unit area, taking into account the angle to the sun [W/m^2] + double detectable_angle_rad_; //!< half angle (>0) [rad] + bool sun_detected_flag_ = false; //!< Sun detected flag // Noise parameters - libra::NormalRand nrs_alpha_; //!< Normal random for alpha angle - libra::NormalRand nrs_beta_; //!< Normal random for beta angle - double bias_alpha_ = 0.0; //!< Constant bias for alpha angle (Value is calculated by random number generator) - double bias_beta_ = 0.0; //!< Constant bias for beta angle (Value is calculated by random number generator) + libra::NormalRand random_noise_alpha_; //!< Normal random for alpha angle + libra::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) // Measured variables - const SolarRadiationPressureEnvironment* srp_; //!< Solar Radiation Pressure environment - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information + const SolarRadiationPressureEnvironment* srp_; //!< Solar Radiation Pressure environment + const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information // functions /** diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 29c9fe082..b5e25a93a 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -27,7 +27,7 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern num_of_logged_stars_(num_of_logged_stars), attitude_(attitude), hipp_(hipp), - local_celes_info_(local_celestial_information) { + local_celestial_information_(local_celestial_information) { is_sun_in_forbidden_angle = true; is_earth_in_forbidden_angle = true; is_moon_in_forbidden_angle = true; @@ -59,13 +59,13 @@ Telescope::~Telescope() {} void Telescope::MainRoutine(int count) { UNUSED(count); // Check forbidden angle - is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_rad_); - is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_rad_); - is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celes_info_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_rad_); + is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_rad_); + is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_rad_); + is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_rad_); // Position calculation of celestial bodies from CelesInfo - Observe(sun_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("SUN")); - Observe(earth_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("EARTH")); - Observe(moon_pos_imgsensor, local_celes_info_->GetPositionFromSpacecraft_b_m("MOON")); + Observe(sun_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN")); + Observe(earth_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH")); + Observe(moon_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON")); // Position calculation of stars from Hipparcos Catalogue // No update when Hipparocos Catalogue was not readed if (hipp_->IsCalcEnabled) ObserveStars(); diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 0d4e030ba..36f9dc2db 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -98,9 +98,9 @@ class Telescope : public Component, public ILoggable { */ void ObserveStars(); - const Attitude* attitude_; //!< Attitude information - const HipparcosCatalogue* hipp_; //!< Star information - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information + const Attitude* attitude_; //!< Attitude information + const HipparcosCatalogue* hipp_; //!< Star information + const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information // Override ILoggable /** diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 3189933c6..869c14ba6 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -20,7 +20,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - local_celes_info_(local_celestial_information), + local_celestial_information_(local_celestial_information), compo_step_time_(compo_step_time) { voltage_ = 0.0; power_generation_ = 0.0; @@ -55,7 +55,7 @@ SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - local_celes_info_(local_celestial_information), + local_celestial_information_(local_celestial_information), compo_step_time_(0.1) { voltage_ = 0.0; power_generation_ = 0.0; @@ -71,7 +71,7 @@ SAP::SAP(const SAP& obj) cell_efficiency_(obj.cell_efficiency_), transmission_efficiency_(obj.transmission_efficiency_), srp_(obj.srp_), - local_celes_info_(obj.local_celes_info_), + local_celestial_information_(obj.local_celestial_information_), compo_step_time_(obj.compo_step_time_) { voltage_ = 0.0; power_generation_ = 0.0; @@ -106,7 +106,7 @@ void SAP::MainRoutine(int time_count) { cell_area_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, normalized_sun_direction_body); } else { const auto power_density = srp_->GetPowerDensity_W_m2(); - libra::Vector<3> sun_pos_b = local_celes_info_->GetPositionFromSpacecraft_b_m("SUN"); + libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = libra::Normalize(sun_pos_b); power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, sun_dir_b); diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index b5329762a..9db9e3082 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -113,8 +113,8 @@ class SAP : public Component, public ILoggable { const double cell_efficiency_; //!< Power generation efficiency of solar cell const double transmission_efficiency_; //!< Efficiency of transmission to PCU - const SolarRadiationPressureEnvironment* const srp_; //!< Solar Radiation Pressure environment - const LocalCelestialInformation* local_celes_info_; //!< Local celestial information + const SolarRadiationPressureEnvironment* const srp_; //!< Solar Radiation Pressure environment + const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information double voltage_; //!< Voltage [V] double power_generation_; //!< Generated power [W] diff --git a/src/dynamics/thermal/node.cpp b/src/dynamics/thermal/node.cpp index eea700ad5..2c1066718 100644 --- a/src/dynamics/thermal/node.cpp +++ b/src/dynamics/thermal/node.cpp @@ -19,7 +19,7 @@ Node::Node(const int node_id, const string node_label, const int heater_node_id, temperature_(temperature_ini), capacity_(capacity_ini), internal_heat_(internal_heat_ini), - alpha_(alpha), + alpha_rad_(alpha), area_(area), normal_v_b_(normal_v_b) { solar_radiation_ = 0; @@ -68,7 +68,7 @@ double Node::CalcSolarRadiation(libra::Vector<3> sun_direction) { // calculate sun_power if (cos_theta > 0) - solar_radiation_ = S * area_ * alpha_ * cos_theta; + solar_radiation_ = S * area_ * alpha_rad_ * cos_theta; else solar_radiation_ = 0; return solar_radiation_; //[W] @@ -78,7 +78,7 @@ void Node::PrintParam(void) { cout << "node_id: " << node_id_ << endl; cout << " node_label : " << node_label_ << endl; cout << " temperature : " << temperature_ << endl; - cout << " alpha : " << alpha_ << endl; + cout << " alpha : " << alpha_rad_ << endl; cout << " capacity : " << capacity_ << endl; cout << " internal heat; " << internal_heat_ << endl; cout << " Normal Vector: "; diff --git a/src/dynamics/thermal/node.hpp b/src/dynamics/thermal/node.hpp index e0932036e..ae1a1e070 100644 --- a/src/dynamics/thermal/node.hpp +++ b/src/dynamics/thermal/node.hpp @@ -18,7 +18,7 @@ class Node { double temperature_; // 温度[K] double capacity_; // 熱容量[J/K] double internal_heat_; // 内部生成熱[J] - double alpha_; + double alpha_rad_; double area_; // 太陽熱が入射する面の面積[m^2] libra::Vector<3> normal_v_b_; // 太陽熱が入射する面の法線ベクトル(機体固定座標系) double solar_radiation_; // 入射する太陽輻射熱[W]([J]に変換するためには時間をかけないといけないことに注意 From d097cac06a043fa03124072a5edb5478eb54310d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:43:25 +0100 Subject: [PATCH 0822/1086] Fix function argument name --- src/components/real/aocs/sun_sensor.cpp | 22 +++++++++++----------- src/components/real/aocs/sun_sensor.hpp | 16 ++++++++-------- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 54b1b7eb3..ec1ee9464 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -14,9 +14,9 @@ using libra::NormalRand; using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, - const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information) + const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, + const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -24,13 +24,13 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celestial_information_(local_celestial_information) { - Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); + Initialize(normal_random_standard_deviation_c_Am2, bias_noise_standard_deviation_rad); } SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, - const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information) + const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), @@ -38,18 +38,18 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celestial_information_(local_celestial_information) { - Initialize(normal_random_standard_deviation_c_Am2, nr_bias_stddev_c); + Initialize(normal_random_standard_deviation_c_Am2, bias_noise_standard_deviation_rad); } -void SunSensor::Initialize(const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c) { +void SunSensor::Initialize(const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad) { // Bias - NormalRand nr(0.0, nr_bias_stddev_c, global_randomization.MakeSeed()); + NormalRand nr(0.0, bias_noise_standard_deviation_rad, global_randomization.MakeSeed()); bias_noise_alpha_rad_ += nr; bias_noise_beta_rad_ += nr; // Normal Random - random_noise_alpha_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() - random_noise_beta_.SetParameters(0.0, normal_random_standard_deviation_c_Am2); // global_randomization.MakeSeed() + random_noise_alpha_.SetParameters(0.0, random_noise_standard_deviation_rad); // global_randomization.MakeSeed() + random_noise_beta_.SetParameters(0.0, random_noise_standard_deviation_rad); // global_randomization.MakeSeed() } void SunSensor::MainRoutine(int count) { UNUSED(count); diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 603f6aa36..b0d21ac04 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -30,13 +30,13 @@ class SunSensor : public Component, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] - * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] + * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c, + const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); /** @@ -49,15 +49,15 @@ class SunSensor : public Component, public ILoggable { * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] - * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] + * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, - const double nr_bias_stddev_c, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information); + const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, + const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); // Override functions for Component /** @@ -130,10 +130,10 @@ class SunSensor : public Component, public ILoggable { /** * @fn TanRange * @brief Clip angle as tangent range - * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] - * @param [in] nr_bias_stddev_c: Standard deviation of normal random noise for bias in the component frame [rad] + * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] + * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] */ - void Initialize(const double normal_random_standard_deviation_c_Am2, const double nr_bias_stddev_c); + void Initialize(const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad); /** * @fn CalcSolarIlluminance * @brief Calculate solar illuminance on the sun sensor surface From c51e79e77732908de04aced0cd24d1a47979e0dd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:44:24 +0100 Subject: [PATCH 0823/1086] Rename private function name --- src/components/real/aocs/star_sensor.cpp | 4 ++-- src/components/real/aocs/star_sensor.hpp | 4 ++-- src/components/real/aocs/sun_sensor.cpp | 4 ++-- src/components/real/aocs/sun_sensor.hpp | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index a2b6808b1..b310b6664 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -87,7 +87,7 @@ void StarSensor::Initialize() { error_flag_ = true; } -Quaternion StarSensor::measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { +Quaternion StarSensor::Measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude) { update(local_celestial_information, attitude); // update delay buffer if (update_count_ == 0) { int hist = buffer_position_ - output_delay_ - 1; @@ -210,5 +210,5 @@ double StarSensor::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& void StarSensor::MainRoutine(const int time_count) { UNUSED(time_count); - measure(&(local_environment_->GetCelestialInformation()), &(dynamics_->GetAttitude())); + Measure(&(local_environment_->GetCelestialInformation()), &(dynamics_->GetAttitude())); } diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 90be051ea..6ee12efe0 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -148,12 +148,12 @@ class StarSensor : public Component, public ILoggable { */ void update(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); /** - * @fn measure + * @fn Measure * @brief Calculate measured quaternion * @param [in] local_celestial_information: Local celestial information * @param [in] attitude: Attitude information */ - libra::Quaternion measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); + libra::Quaternion Measure(const LocalCelestialInformation* local_celestial_information, const Attitude* attitude); /** * @fn AllJudgement diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index ec1ee9464..86fc61e42 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -54,10 +54,10 @@ void SunSensor::Initialize(const double random_noise_standard_deviation_rad, con void SunSensor::MainRoutine(int count) { UNUSED(count); - measure(); + Measure(); } -void SunSensor::measure() { +void SunSensor::Measure() { libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = Normalize(sun_pos_b); diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index b0d21ac04..af40719de 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -116,10 +116,10 @@ class SunSensor : public Component, public ILoggable { */ void SunDetectionJudgement(); /** - * @fn measure + * @fn Measure * @brief Calculate observed sun angle */ - void measure(); + void Measure(); /** * @fn TanRange * @brief Clip angle as tangent range From b3b81dad3f9692d67292ff036f38eac67ea7390b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:45:59 +0100 Subject: [PATCH 0824/1086] Fix function argument name --- src/components/real/aocs/sun_sensor.cpp | 8 ++++---- src/components/real/aocs/sun_sensor.hpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 86fc61e42..0a27d36fe 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -14,7 +14,7 @@ using libra::NormalRand; using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, + const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator), @@ -24,11 +24,11 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celestial_information_(local_celestial_information) { - Initialize(normal_random_standard_deviation_c_Am2, bias_noise_standard_deviation_rad); + Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator, power_port), @@ -38,7 +38,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power detectable_angle_rad_(detectable_angle_rad), srp_(srp), local_celestial_information_(local_celestial_information) { - Initialize(normal_random_standard_deviation_c_Am2, bias_noise_standard_deviation_rad); + Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } void SunSensor::Initialize(const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad) { diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index af40719de..8779b9fa6 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -29,14 +29,14 @@ class SunSensor : public Component, public ILoggable { * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] - * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] + * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, - const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, const double bias_noise_standard_deviation_rad, + const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); /** @@ -48,14 +48,14 @@ class SunSensor : public Component, public ILoggable { * @param [in] component_id: Sensor ID * @param [in] quaternion_b2c: Quaternion from body frame to component frame * @param [in] detectable_angle_rad: Detectable angle threshold [rad] - * @param [in] normal_random_standard_deviation_c_Am2: Standard deviation of normal random noise in the component frame [rad] + * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double normal_random_standard_deviation_c_Am2, + const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); From e7b1ff2cee8a6002387dc9d01963f9c944a36415 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:47:43 +0100 Subject: [PATCH 0825/1086] Fix public function names --- src/components/real/aocs/sun_sensor.cpp | 4 ++-- src/components/real/aocs/sun_sensor.hpp | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 0a27d36fe..88650648d 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -51,8 +51,8 @@ void SunSensor::Initialize(const double random_noise_standard_deviation_rad, con random_noise_alpha_.SetParameters(0.0, random_noise_standard_deviation_rad); // global_randomization.MakeSeed() random_noise_beta_.SetParameters(0.0, random_noise_standard_deviation_rad); // global_randomization.MakeSeed() } -void SunSensor::MainRoutine(int count) { - UNUSED(count); +void SunSensor::MainRoutine(const int time_count) { + UNUSED(time_count); Measure(); } diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 8779b9fa6..dfbdadaf3 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -64,7 +64,7 @@ class SunSensor : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine for sensor observation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** @@ -80,11 +80,11 @@ class SunSensor : public Component, public ILoggable { // Getter inline bool GetSunDetectedFlag() const { return sun_detected_flag_; }; - inline const libra::Vector<3> GetMeasuredSun_c() const { return measured_sun_direction_c_; }; - inline const libra::Vector<3> GetMeasuredSun_b() const { return quaternion_b2c_.Conjugate().FrameConversion(measured_sun_direction_c_); }; - inline double GetSunAngleAlpha() const { return alpha_rad_; }; - inline double GetSunAngleBeta() const { return beta_rad_; }; - inline double GetSolarIlluminance() const { return solar_illuminance_W_m2_; }; + inline const libra::Vector<3> GetMeasuredSunDirection_c() const { return measured_sun_direction_c_; }; + inline const libra::Vector<3> GetMeasuredSunDirection_b() const { return quaternion_b2c_.Conjugate().FrameConversion(measured_sun_direction_c_); }; + inline double GetSunAngleAlpha_rad() const { return alpha_rad_; }; + inline double GetSunAngleBeta_rad() const { return beta_rad_; }; + inline double GetSolarIlluminance_W_m2() const { return solar_illuminance_W_m2_; }; protected: const int component_id_; //!< Sensor ID From 955ebe3a5c10cad28a4e080dfe37e33e2bad1b21 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:49:24 +0100 Subject: [PATCH 0826/1086] Fix function argument names --- .../real/aocs/initialize_gnss_receiver.cpp | 14 +++++++------- .../real/aocs/initialize_gnss_receiver.hpp | 8 ++++---- .../real/aocs/initialize_gyro_sensor.cpp | 14 +++++++------- .../real/aocs/initialize_gyro_sensor.hpp | 8 ++++---- .../real/aocs/initialize_magnetometer.cpp | 14 +++++++------- .../real/aocs/initialize_magnetometer.hpp | 8 ++++---- .../real/aocs/initialize_magnetorquer.cpp | 10 +++++----- .../real/aocs/initialize_magnetorquer.hpp | 10 +++++----- .../real/aocs/initialize_star_sensor.cpp | 10 +++++----- .../real/aocs/initialize_star_sensor.hpp | 8 ++++---- src/components/real/aocs/initialize_sun_sensor.hpp | 8 ++++---- .../initialize_ground_station_calculator.cpp | 4 ++-- .../initialize_ground_station_calculator.hpp | 4 ++-- .../real/mission/initialize_telescope.cpp | 4 ++-- .../real/mission/initialize_telescope.hpp | 4 ++-- .../real/power/csv_scenario_interface.cpp | 4 ++-- .../real/power/csv_scenario_interface.hpp | 4 ++-- src/components/real/power/initialize_battery.cpp | 4 ++-- src/components/real/power/initialize_battery.hpp | 4 ++-- .../real/power/initialize_pcu_initial_study.cpp | 4 ++-- .../real/power/initialize_pcu_initial_study.hpp | 4 ++-- .../real/power/initialize_solar_array_panel.cpp | 8 ++++---- .../real/power/initialize_solar_array_panel.hpp | 8 ++++---- .../real/propulsion/initialize_simple_thruster.cpp | 10 +++++----- .../real/propulsion/initialize_simple_thruster.hpp | 8 ++++---- 25 files changed, 93 insertions(+), 93 deletions(-) diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index 046b2c064..e9befefa9 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -19,10 +19,10 @@ typedef struct _gnssrecever_param { Vector<3> noise_standard_deviation_m; } GnssReceiverParam; -GnssReceiverParam ReadGnssReceiverIni(const std::string fname, const GnssSatellites* gnss_satellites, const int component_id) { +GnssReceiverParam ReadGnssReceiverIni(const std::string file_name, const GnssSatellites* gnss_satellites, const int component_id) { GnssReceiverParam gnssreceiver_param; - IniAccess gnssr_conf(fname); + IniAccess gnssr_conf(file_name); const char* sensor_name = "GNSS_RECEIVER_"; const std::string section_name = sensor_name + std::to_string(static_cast(component_id)); const char* GSection = section_name.c_str(); @@ -49,9 +49,9 @@ GnssReceiverParam ReadGnssReceiverIni(const std::string fname, const GnssSatelli return gnssreceiver_param; } -GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string fname, const Dynamics* dynamics, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string file_name, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { - GnssReceiverParam gr_param = ReadGnssReceiverIni(fname, gnss_satellites, component_id); + GnssReceiverParam gr_param = ReadGnssReceiverIni(file_name, gnss_satellites, component_id); GnssReceiver gnss_r(gr_param.prescaler, clock_generator, component_id, gr_param.gnss_id, gr_param.max_channel, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, @@ -59,12 +59,12 @@ GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, return gnss_r; } -GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string fname, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string file_name, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time) { - GnssReceiverParam gr_param = ReadGnssReceiverIni(fname, gnss_satellites, component_id); + GnssReceiverParam gr_param = ReadGnssReceiverIni(file_name, gnss_satellites, component_id); // PowerPort - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); GnssReceiver gnss_r(gr_param.prescaler, clock_generator, power_port, component_id, gr_param.gnss_id, gr_param.max_channel, gr_param.antenna_model, gr_param.antenna_pos_b, gr_param.quaternion_b2c, gr_param.half_width_rad, gr_param.noise_standard_deviation_m, dynamics, diff --git a/src/components/real/aocs/initialize_gnss_receiver.hpp b/src/components/real/aocs/initialize_gnss_receiver.hpp index ec05b3c5b..d2b04bba6 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.hpp +++ b/src/components/real/aocs/initialize_gnss_receiver.hpp @@ -13,12 +13,12 @@ * @brief Initialize functions for GNSS Receiver without power port * @param [in] clock_generator: Clock generator * @param [in] component_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information * @param [in] simulation_time: Simulation time information */ -GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string fname, const Dynamics* dynamics, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string file_name, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); /** * @fn InitGnssReceiver @@ -26,12 +26,12 @@ GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, * @param [in] clock_generator: Clock generator * @param [in] component_id: Sensor ID * @param [in] power_port: Power port - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information * @param [in] gnss_satellites: GNSS satellites information * @param [in] simulation_time: Simulation time information */ -GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string fname, +GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, PowerPort* power_port, int component_id, const std::string file_name, const Dynamics* dynamics, const GnssSatellites* gnss_satellites, const SimulationTime* simulation_time); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GNSS_RECEIVER_HPP_ diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 06e793a79..69c51a821 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -8,8 +8,8 @@ #include "../../base/initialize_sensor.hpp" -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics) { - IniAccess gyro_conf(fname); +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics) { + IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); @@ -20,16 +20,16 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::s if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), GSection, "rad_s"); GyroSensor gyro(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics) { - IniAccess gyro_conf(fname); + IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); @@ -40,10 +40,10 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(fname, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), GSection, "rad_s"); // PowerPort - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); GyroSensor gyro(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; diff --git a/src/components/real/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp index f22c34e9f..7ff7273e5 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -14,10 +14,10 @@ * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] compo_step_time: Component step time [sec] - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics); +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics); /** * @fn InitGyro * @brief Initialize functions for gyro sensor with power port @@ -25,10 +25,10 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::s * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] compo_step_time: Component step time [sec] - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index 0e490a41e..bf69f255d 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,9 +7,9 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field) { - IniAccess magsensor_conf(fname); + IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* MSSection = section_name.c_str(); @@ -22,15 +22,15 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const // Sensor Sensor sensor_base = - ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), MSSection, "nT"); Magnetometer magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field) { - IniAccess magsensor_conf(fname); + IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* MSSection = section_name.c_str(); @@ -43,10 +43,10 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_por // Sensor Sensor sensor_base = - ReadSensorInformation(fname, compo_step_time * (double)(prescaler), MSSection, "nT"); + ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), MSSection, "nT"); // PowerPort - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); Magnetometer magsensor(prescaler, clock_generator, power_port, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index e362fa6ee..8352efe3d 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -13,11 +13,11 @@ * @brief Initialize functions for magnetometer without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field); /** * @fn InitMagSensor @@ -25,11 +25,11 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 804368291..ad1558edd 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -6,9 +6,9 @@ #include "library/initialize/initialize_file_access.hpp" -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field) { - IniAccess magtorquer_conf(fname); + IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); const char* MTSection = section_name.c_str(); @@ -51,9 +51,9 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co return magtorquer; } -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field) { - IniAccess magtorquer_conf(fname); + IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); const char* MTSection = section_name.c_str(); @@ -91,7 +91,7 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_po magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); // PowerPort - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); Magnetorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index edf9bf5e9..f7f66fe9b 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -13,11 +13,11 @@ * @brief Initialize functions for magnetometer without power port * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string fname, double compo_step_time, +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double compo_step_time, const GeomagneticField* geomagnetic_field); /** * @fn InitMagTorquer @@ -25,11 +25,11 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] actuator_id: Actuator ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string fname, double compo_step_time, - const GeomagneticField* geomagnetic_field); +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, + double compo_step_time, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index ad1d32ed2..a382a9172 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -10,9 +10,9 @@ using namespace std; -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string fname, double compo_step_time, const Dynamics* dynamics, +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string file_name, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_environment) { - IniAccess STT_conf(fname); + IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* STTSection = section_name.c_str(); @@ -43,9 +43,9 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string return stt; } -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string fname, double compo_step_time, +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string file_name, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_environment) { - IniAccess STT_conf(fname); + IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* STTSection = section_name.c_str(); @@ -71,7 +71,7 @@ StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int s double capture_rate_deg_s = STT_conf.ReadDouble(STTSection, "angular_rate_limit_deg_s"); double capture_rate_rad_s = capture_rate_deg_s * libra::pi / 180.0; - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); StarSensor stt(prescaler, clock_generator, power_port, sensor_id, quaternion_b2c, standard_deviation_orthogonal_direction, standard_deviation_sight_direction, step_time_s, output_delay, output_interval, sun_forbidden_angle_rad, earth_forbidden_angle_rad, diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index c3e0ee902..d3a9fd8a7 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -13,12 +13,12 @@ * @brief Initialize functions for StarSensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string fname, double compo_step_time, const Dynamics* dynamics, +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_environment); /** * @fn InitSTT @@ -26,12 +26,12 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::st * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] compo_step_time: Component step time [sec] * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, double compo_step_time, +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics, const LocalEnvironment* local_environment); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index 688282b3f..be94bb1d2 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -13,11 +13,11 @@ * @brief Initialize functions for sun sensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] srp: Solar radiation pressure environment * @param [in] local_environment: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); /** * @fn InitSunSensor @@ -25,11 +25,11 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to the initialize file + * @param [in] file_name: Path to the initialize file * @param [in] srp: Solar radiation pressure environment * @param [in] local_environment: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string fname, +SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index f9f7a22f3..b015afb5c 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -10,8 +10,8 @@ #include "library/initialize/initialize_file_access.hpp" -GScalculator InitGScalculator(const std::string fname) { - IniAccess gs_conf(fname); +GScalculator InitGScalculator(const std::string file_name) { + IniAccess gs_conf(file_name); char Section[30] = "GROUND_STATION_CALCULATOR"; diff --git a/src/components/real/communication/initialize_ground_station_calculator.hpp b/src/components/real/communication/initialize_ground_station_calculator.hpp index 776a73280..2861fe88c 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.hpp +++ b/src/components/real/communication/initialize_ground_station_calculator.hpp @@ -11,9 +11,9 @@ /* * @fn InitGscalculator * @brief Initialize function for Ground Station Calculator - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file */ -GScalculator InitGScalculator(const std::string fname); +GScalculator InitGScalculator(const std::string file_name); #endif // S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index 8f80772a0..a78a2f29c 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -13,11 +13,11 @@ using namespace std; -Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string fname, const Attitude* attitude, const HipparcosCatalogue* hipp, +Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string file_name, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information) { using libra::pi; - IniAccess Telescope_conf(fname); + IniAccess Telescope_conf(file_name); const string st_sensor_id = std::to_string(static_cast(sensor_id)); const char* cs = st_sensor_id.data(); diff --git a/src/components/real/mission/initialize_telescope.hpp b/src/components/real/mission/initialize_telescope.hpp index 898fc3aff..152b28fa4 100644 --- a/src/components/real/mission/initialize_telescope.hpp +++ b/src/components/real/mission/initialize_telescope.hpp @@ -13,12 +13,12 @@ * @brief Initialize function of Telescope * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] attitude: Attitude information * @param [in] hipp: Star information by Hipparcos catalogue * @param [in] local_celestial_information: Local celestial information */ -Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const std::string fname, const Attitude* attitude, +Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, const Attitude* attitude, const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/real/power/csv_scenario_interface.cpp b/src/components/real/power/csv_scenario_interface.cpp index 732fc0452..4c999b0eb 100644 --- a/src/components/real/power/csv_scenario_interface.cpp +++ b/src/components/real/power/csv_scenario_interface.cpp @@ -11,8 +11,8 @@ bool CsvScenarioInterface::is_csv_senario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; std::map CsvScenarioInterface::buffers_; -void CsvScenarioInterface::Initialize(const std::string fname) { - IniAccess scenario_conf(fname); +void CsvScenarioInterface::Initialize(const std::string file_name) { + IniAccess scenario_conf(file_name); char Section[30] = "SCENARIO"; CsvScenarioInterface::is_csv_senario_enabled_ = scenario_conf.ReadBoolean(Section, "is_csv_scenario_enabled"); diff --git a/src/components/real/power/csv_scenario_interface.hpp b/src/components/real/power/csv_scenario_interface.hpp index fbae784a9..6b9f1cadc 100644 --- a/src/components/real/power/csv_scenario_interface.hpp +++ b/src/components/real/power/csv_scenario_interface.hpp @@ -22,9 +22,9 @@ class CsvScenarioInterface { /** * @fn Initialize * @brief Initialize function - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file */ - static void Initialize(const std::string fname); + static void Initialize(const std::string file_name); /** * @fn IsCsvScenarioEnabled diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index 6ffbe404f..27dc171c6 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -10,8 +10,8 @@ #include "library/initialize/initialize_file_access.hpp" -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string fname, double compo_step_time) { - IniAccess bat_conf(fname); +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double compo_step_time) { + IniAccess bat_conf(file_name); const std::string st_bat_id = std::to_string(bat_id); const char* cs = st_bat_id.data(); diff --git a/src/components/real/power/initialize_battery.hpp b/src/components/real/power/initialize_battery.hpp index d4a12f084..7f3491347 100644 --- a/src/components/real/power/initialize_battery.hpp +++ b/src/components/real/power/initialize_battery.hpp @@ -13,9 +13,9 @@ * @brief Initialize function of BAT * @param [in] clock_generator: Clock generator * @param [in] bat_id: Battery ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] compo_step_time: Component step time [sec] */ -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string fname, double compo_step_time); +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 065fed39a..b0b630a74 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -11,9 +11,9 @@ #include "library/initialize/initialize_file_access.hpp" -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, double compo_step_time) { - IniAccess pcu_conf(fname); + IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); const char* cs = st_pcu_id.data(); diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index b56712196..c3f84e2b8 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -13,12 +13,12 @@ * @brief Initialize function of BAT * @param [in] clock_generator: Clock generator * @param [in] pcu_id: Power Control Unit ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] sap: Solar Array Panel infomation * @param [in] bat: Battery information * @param [in] compo_step_time: Component step time [sec] */ -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string fname, const std::vector saps, BAT* bat, +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index 66c59f739..1b1f0edf8 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -9,9 +9,9 @@ #include "library/initialize/initialize_file_access.hpp" -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information, double compo_step_time) { - IniAccess sap_conf(fname); + IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); const char* cs = st_sap_id.data(); @@ -46,9 +46,9 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname return sap; } -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, double compo_step_time) { - IniAccess sap_conf(fname); + IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); const char* cs = st_sap_id.data(); diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index cfc8f7992..43f68d39d 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -13,12 +13,12 @@ * @brief Initialize function of BAT * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information, double compo_step_time); /* @@ -26,11 +26,11 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname * @brief Initialize function of BAT * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment * @param [in] compo_step_time: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string fname, const SolarRadiationPressureEnvironment* srp, +SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, double compo_step_time); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/real/propulsion/initialize_simple_thruster.cpp b/src/components/real/propulsion/initialize_simple_thruster.cpp index 3743a2792..745aef3ea 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.cpp +++ b/src/components/real/propulsion/initialize_simple_thruster.cpp @@ -8,9 +8,9 @@ #include "library/initialize/initialize_file_access.hpp" -SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string fname, const Structure* structure, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string file_name, const Structure* structure, const Dynamics* dynamics) { - IniAccess thruster_conf(fname); + IniAccess thruster_conf(file_name); std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); auto* Section = sectionstr.c_str(); @@ -35,9 +35,9 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_ return thruster; } -SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string fname, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string file_name, const Structure* structure, const Dynamics* dynamics) { - IniAccess thruster_conf(fname); + IniAccess thruster_conf(file_name); std::string sectionstr = "THRUSTER_" + std::to_string(thruster_id); auto* Section = sectionstr.c_str(); @@ -58,7 +58,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* po double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; - power_port->InitializeWithInitializeFile(fname); + power_port->InitializeWithInitializeFile(file_name); SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); diff --git a/src/components/real/propulsion/initialize_simple_thruster.hpp b/src/components/real/propulsion/initialize_simple_thruster.hpp index ddea0706a..bdb7b5381 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.hpp +++ b/src/components/real/propulsion/initialize_simple_thruster.hpp @@ -13,11 +13,11 @@ * @brief Initialize function os SimpleThruster * @param [in] clock_generator: Clock generator * @param [in] thruster_id: Thruster ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ -SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string fname, const Structure* structure, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_id, const std::string file_name, const Structure* structure, const Dynamics* dynamics); /** * @fn InitSimpleThruster @@ -25,11 +25,11 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_ * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] thruster_id: Thruster ID - * @param [in] fname: Path to initialize file + * @param [in] file_name: Path to initialize file * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ -SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string fname, +SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* power_port, int thruster_id, const std::string file_name, const Structure* structure, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_PROPULSION_INITIALIZE_SIMPLE_THRUSTER_HPP_ From 772cc3ad5317cd84859df07aff79c6aeb28cee00 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:50:42 +0100 Subject: [PATCH 0827/1086] Fix function argument names --- src/components/real/aocs/initialize_gyro_sensor.cpp | 11 +++++++---- src/components/real/aocs/initialize_gyro_sensor.hpp | 9 +++++---- src/components/real/aocs/initialize_magnetometer.cpp | 10 +++++----- src/components/real/aocs/initialize_magnetometer.hpp | 10 +++++----- src/components/real/aocs/initialize_magnetorquer.cpp | 10 +++++----- src/components/real/aocs/initialize_magnetorquer.hpp | 8 ++++---- src/components/real/aocs/initialize_star_sensor.cpp | 8 ++++---- src/components/real/aocs/initialize_star_sensor.hpp | 10 +++++----- src/components/real/power/battery.cpp | 4 ++-- src/components/real/power/battery.hpp | 6 +++--- src/components/real/power/initialize_battery.cpp | 4 ++-- src/components/real/power/initialize_battery.hpp | 4 ++-- .../real/power/initialize_pcu_initial_study.cpp | 4 ++-- .../real/power/initialize_pcu_initial_study.hpp | 4 ++-- .../real/power/initialize_solar_array_panel.cpp | 8 ++++---- .../real/power/initialize_solar_array_panel.hpp | 8 ++++---- src/components/real/power/pcu_initial_study.cpp | 4 ++-- src/components/real/power/pcu_initial_study.hpp | 4 ++-- src/components/real/power/solar_array_panel.cpp | 8 ++++---- src/components/real/power/solar_array_panel.hpp | 8 ++++---- 20 files changed, 73 insertions(+), 69 deletions(-) diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 69c51a821..5f59170c4 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -8,7 +8,8 @@ #include "../../base/initialize_sensor.hpp" -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics) { +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics) { IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -20,14 +21,15 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::s if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = + ReadSensorInformation(file_name, component_step_time_s * (double)(prescaler), GSection, "rad_s"); GyroSensor gyro(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, dynamics); return gyro; } -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, const Dynamics* dynamics) { IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; @@ -40,7 +42,8 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int if (prescaler <= 1) prescaler = 1; // Sensor - Sensor sensor_base = ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), GSection, "rad_s"); + Sensor sensor_base = + ReadSensorInformation(file_name, component_step_time_s * (double)(prescaler), GSection, "rad_s"); // PowerPort power_port->InitializeWithInitializeFile(file_name); diff --git a/src/components/real/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp index 7ff7273e5..7fe6d52ca 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -13,22 +13,23 @@ * @brief Initialize functions for gyro sensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics); +GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics); /** * @fn InitGyro * @brief Initialize functions for gyro sensor with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, +GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index bf69f255d..b6501c3e7 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,7 +7,7 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; @@ -22,14 +22,14 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const // Sensor Sensor sensor_base = - ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), MSSection, "nT"); + ReadSensorInformation(file_name, component_step_time_s * (double)(prescaler), MSSection, "nT"); Magnetometer magsensor(prescaler, clock_generator, sensor_base, sensor_id, quaternion_b2c, geomagnetic_field); return magsensor; } -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -43,7 +43,7 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_por // Sensor Sensor sensor_base = - ReadSensorInformation(file_name, compo_step_time * (double)(prescaler), MSSection, "nT"); + ReadSensorInformation(file_name, component_step_time_s * (double)(prescaler), MSSection, "nT"); // PowerPort power_port->InitializeWithInitializeFile(file_name); diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 8352efe3d..2d8ec4e6b 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -14,10 +14,10 @@ * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, +Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, const GeomagneticField* geomagnetic_field); /** * @fn InitMagSensor @@ -26,10 +26,10 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] mgnet: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, - const GeomagneticField* geomagnetic_field); +Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index ad1558edd..9419a91be 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -6,7 +6,7 @@ #include "library/initialize/initialize_file_access.hpp" -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double compo_step_time, +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; @@ -37,7 +37,7 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); - double random_walk_step_width_s = compo_step_time * (double)prescaler; + double random_walk_step_width_s = component_step_time_s * (double)prescaler; Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); Vector random_walk_limit_c_Am2; @@ -51,8 +51,8 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co return magtorquer; } -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, double compo_step_time, - const GeomagneticField* geomagnetic_field) { +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -82,7 +82,7 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_po Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); - double random_walk_step_width_s = compo_step_time * (double)prescaler; + double random_walk_step_width_s = component_step_time_s * (double)prescaler; Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); Vector random_walk_limit_c_Am2; diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index f7f66fe9b..1fc908cce 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -14,10 +14,10 @@ * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double compo_step_time, +Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, const GeomagneticField* geomagnetic_field); /** * @fn InitMagTorquer @@ -26,10 +26,10 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co * @param [in] power_port: Power port * @param [in] actuator_id: Actuator ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, - double compo_step_time, const GeomagneticField* geomagnetic_field); + double component_step_time_s, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index a382a9172..6b76f9294 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -10,7 +10,7 @@ using namespace std; -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string file_name, double compo_step_time, const Dynamics* dynamics, +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string file_name, double component_step_time_s, const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; @@ -19,7 +19,7 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - double step_time_s = compo_step_time * prescaler; + double step_time_s = component_step_time_s * prescaler; Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); double standard_deviation_orthogonal_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); @@ -43,7 +43,7 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string return stt; } -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string file_name, double compo_step_time, +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string file_name, double component_step_time_s, const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; @@ -52,7 +52,7 @@ StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int s int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - double step_time_s = compo_step_time * prescaler; + double step_time_s = component_step_time_s * prescaler; Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index d3a9fd8a7..58f3d2bf7 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -14,12 +14,12 @@ * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double compo_step_time, const Dynamics* dynamics, - const LocalEnvironment* local_environment); +StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment); /** * @fn InitSTT * @brief Initialize functions for StarSensor with power port @@ -27,11 +27,11 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::st * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double compo_step_time, +StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, const Dynamics* dynamics, const LocalEnvironment* local_environment); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 75cc66c6d..ec0404b2b 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -9,7 +9,7 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance, double compo_step_time) + double bat_resistance, double component_step_time_s) : Component(prescaler, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -19,7 +19,7 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_ser cv_charge_voltage_(cv_charge_voltage), dod_(initial_dod), bat_resistance_(bat_resistance), - compo_step_time_(compo_step_time) {} + compo_step_time_(component_step_time_s) {} BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 65ff14764..a988db08d 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -30,11 +30,11 @@ class BAT : public Component, public ILoggable { * @param [in] cc_charge_c_rate: Constant charge current [C] * @param [in] cv_charge_voltage: Constant charge voltage [V] * @param [in] bat_resistance: Battery internal resistance [Ohm] - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance, double compo_step_time); + double bat_resistance, double component_step_time_s); /** * @fn BAT * @brief Constructor without prescaler @@ -48,7 +48,7 @@ class BAT : public Component, public ILoggable { * @param [in] cc_charge_c_rate: Constant charge current [C] * @param [in] cv_charge_voltage: Constant charge voltage [V] * @param [in] bat_resistance: Battery internal resistance [Ohm] - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index 27dc171c6..c4053becc 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double compo_step_time) { +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s) { IniAccess bat_conf(file_name); const std::string st_bat_id = std::to_string(bat_id); @@ -52,7 +52,7 @@ BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_ bat_resistance = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); BAT bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity, cell_discharge_curve_coeffs, initial_dod, cc_charge_c_rate, - cv_charge_voltage, bat_resistance, compo_step_time); + cv_charge_voltage, bat_resistance, component_step_time_s); return bat; } diff --git a/src/components/real/power/initialize_battery.hpp b/src/components/real/power/initialize_battery.hpp index 7f3491347..cb89d8747 100644 --- a/src/components/real/power/initialize_battery.hpp +++ b/src/components/real/power/initialize_battery.hpp @@ -14,8 +14,8 @@ * @param [in] clock_generator: Clock generator * @param [in] bat_id: Battery ID * @param [in] file_name: Path to initialize file - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double compo_step_time); +BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index b0b630a74..28c9978ab 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -12,7 +12,7 @@ #include "library/initialize/initialize_file_access.hpp" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, - double compo_step_time) { + double component_step_time_s) { IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); @@ -24,7 +24,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_i int prescaler = pcu_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - PCU_InitialStudy pcu(prescaler, clock_generator, saps, bat, compo_step_time); + PCU_InitialStudy pcu(prescaler, clock_generator, saps, bat, component_step_time_s); return pcu; } diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index c3f84e2b8..e6364848f 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -16,9 +16,9 @@ * @param [in] file_name: Path to initialize file * @param [in] sap: Solar Array Panel infomation * @param [in] bat: Battery information - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, - double compo_step_time); + double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index 1b1f0edf8..0b556f057 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double compo_step_time) { + const LocalCelestialInformation* local_celestial_information, double component_step_time_s) { IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); @@ -41,13 +41,13 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, - transmission_efficiency, srp, local_celestial_information, compo_step_time); + transmission_efficiency, srp, local_celestial_information, component_step_time_s); return sap; } SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - double compo_step_time) { + double component_step_time_s) { IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); @@ -78,7 +78,7 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, - transmission_efficiency, srp, compo_step_time); + transmission_efficiency, srp, component_step_time_s); return sap; } diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index 43f68d39d..f3e783e4f 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -16,10 +16,10 @@ * @param [in] file_name: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double compo_step_time); + const LocalCelestialInformation* local_celestial_information, double component_step_time_s); /* * @fn InitSAP @@ -28,9 +28,9 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ * @param [in] sap_id: SAP ID * @param [in] file_name: Path to initialize file * @param [in] srp: Solar Radiation Pressure environment - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - double compo_step_time); + double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 32318e134..ebfbe7010 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -10,13 +10,13 @@ #include PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, - double compo_step_time) + double component_step_time_s) : Component(prescaler, clock_generator), saps_(saps), bat_(bat), cc_charge_current_(bat->GetCCChargeCurrent()), cv_charge_voltage_(bat->GetCVChargeVoltage()), - compo_step_time_(compo_step_time) { + compo_step_time_(component_step_time_s) { bus_voltage_ = 0.0; power_consumption_ = 0.0; } diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index 310f2ef46..a75737b4d 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -22,9 +22,9 @@ class PCU_InitialStudy : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels * @param [in] bat: Battery - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ - PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, double compo_step_time); + PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, double component_step_time_s); /** * @fn PCU_InitialStudy * @brief Constructor diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 869c14ba6..ea9b5f522 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -10,7 +10,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double compo_step_time) + const LocalCelestialInformation* local_celestial_information, double component_step_time_s) : Component(prescaler, clock_generator), component_id_(component_id), number_of_series_(number_of_series), @@ -21,14 +21,14 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, transmission_efficiency_(transmission_efficiency), srp_(srp), local_celestial_information_(local_celestial_information), - compo_step_time_(compo_step_time) { + compo_step_time_(component_step_time_s) { voltage_ = 0.0; power_generation_ = 0.0; } SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - double compo_step_time) + double component_step_time_s) : Component(prescaler, clock_generator), component_id_(component_id), number_of_series_(number_of_series), @@ -38,7 +38,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - compo_step_time_(compo_step_time) { + compo_step_time_(component_step_time_s) { voltage_ = 0.0; power_generation_ = 0.0; } diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 9db9e3082..dca9f83b8 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -29,11 +29,11 @@ class SAP : public Component, public ILoggable { * @param [in] transmission_efficiency: Efficiency of transmission to PCU * @param [in] srp: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double compo_step_time); + const LocalCelestialInformation* local_celestial_information, double component_step_time_s); /** * @fn SAP * @brief Constructor with prescaler @@ -47,11 +47,11 @@ class SAP : public Component, public ILoggable { * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU * @param [in] srp: Solar Radiation Pressure environment - * @param [in] compo_step_time: Component step time [sec] + * @param [in] component_step_time_s: Component step time [sec] */ SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - double compo_step_time); + double component_step_time_s); /** * @fn SAP * @brief Constructor without prescaler From f9c7f0866265874e3a527d762228f2eeede9ae90 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:53:25 +0100 Subject: [PATCH 0828/1086] Fix initialize function name --- .../real/aocs/initialize_gyro_sensor.cpp | 8 ++++---- .../real/aocs/initialize_gyro_sensor.hpp | 12 ++++++------ .../real/aocs/initialize_magnetometer.cpp | 8 ++++---- .../real/aocs/initialize_magnetometer.hpp | 16 ++++++++-------- .../real/aocs/initialize_magnetorquer.cpp | 8 ++++---- .../real/aocs/initialize_magnetorquer.hpp | 12 ++++++------ .../real/aocs/initialize_reaction_wheel.cpp | 6 +++--- .../real/aocs/initialize_reaction_wheel.hpp | 10 +++++----- .../real/aocs/initialize_star_sensor.cpp | 8 ++++---- .../real/aocs/initialize_star_sensor.hpp | 12 ++++++------ .../sample_spacecraft/sample_components.cpp | 19 ++++++++++--------- 11 files changed, 60 insertions(+), 59 deletions(-) diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 5f59170c4..7c676090a 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -8,8 +8,8 @@ #include "../../base/initialize_sensor.hpp" -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics) { +GyroSensor InitGyroSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics) { IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -29,8 +29,8 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::s return gyro; } -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics) { +GyroSensor InitGyroSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const Dynamics* dynamics) { IniAccess gyro_conf(file_name); const char* sensor_name = "GYRO_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); diff --git a/src/components/real/aocs/initialize_gyro_sensor.hpp b/src/components/real/aocs/initialize_gyro_sensor.hpp index 7fe6d52ca..bb0db7a6e 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.hpp +++ b/src/components/real/aocs/initialize_gyro_sensor.hpp @@ -9,7 +9,7 @@ #include /** - * @fn InitGyro + * @fn InitGyroSensor * @brief Initialize functions for gyro sensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID @@ -17,10 +17,10 @@ * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics); +GyroSensor InitGyroSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics); /** - * @fn InitGyro + * @fn InitGyroSensor * @brief Initialize functions for gyro sensor with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port @@ -29,7 +29,7 @@ GyroSensor InitGyro(ClockGenerator* clock_generator, int sensor_id, const std::s * @param [in] file_name: Path to the initialize file * @param [in] dynamics: Dynamics information */ -GyroSensor InitGyro(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics); +GyroSensor InitGyroSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const Dynamics* dynamics); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_GYRO_SENSOR_HPP_ diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index b6501c3e7..6fa42fba3 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -7,8 +7,8 @@ #include "../../base/initialize_sensor.hpp" #include "library/initialize/initialize_file_access.hpp" -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, - const GeomagneticField* geomagnetic_field) { +Magnetometer InitMagetometer(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -28,8 +28,8 @@ Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const return magsensor; } -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, - double component_step_time_s, const GeomagneticField* geomagnetic_field) { +Magnetometer InitMagetometer(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magsensor_conf(file_name); const char* sensor_name = "MAGNETOMETER_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); diff --git a/src/components/real/aocs/initialize_magnetometer.hpp b/src/components/real/aocs/initialize_magnetometer.hpp index 2d8ec4e6b..6422bfe88 100644 --- a/src/components/real/aocs/initialize_magnetometer.hpp +++ b/src/components/real/aocs/initialize_magnetometer.hpp @@ -9,27 +9,27 @@ #include /** - * @fn InitMagSensor + * @fn InitMagetometer * @brief Initialize functions for magnetometer without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file * @param [in] component_step_time_s: Component step time [sec] - * @param [in] mgnet: Geomegnetic environment + * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, - const GeomagneticField* geomagnetic_field); +Magnetometer InitMagetometer(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const GeomagneticField* geomagnetic_field); /** - * @fn InitMagSensor + * @fn InitMagetometer * @brief Initialize functions for magnetometer with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file * @param [in] component_step_time_s: Component step time [sec] - * @param [in] mgnet: Geomegnetic environment + * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetometer InitMagSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, - double component_step_time_s, const GeomagneticField* geomagnetic_field); +Magnetometer InitMagetometer(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETOMETER_HPP_ diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 9419a91be..15a82aeba 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -6,8 +6,8 @@ #include "library/initialize/initialize_file_access.hpp" -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, - const GeomagneticField* geomagnetic_field) { +Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, + const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); @@ -51,8 +51,8 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co return magtorquer; } -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, - double component_step_time_s, const GeomagneticField* geomagnetic_field) { +Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field) { IniAccess magtorquer_conf(file_name); const char* sensor_name = "MAGNETORQUER_"; const std::string section_name = sensor_name + std::to_string(static_cast(actuator_id)); diff --git a/src/components/real/aocs/initialize_magnetorquer.hpp b/src/components/real/aocs/initialize_magnetorquer.hpp index 1fc908cce..c45f1aa47 100644 --- a/src/components/real/aocs/initialize_magnetorquer.hpp +++ b/src/components/real/aocs/initialize_magnetorquer.hpp @@ -9,7 +9,7 @@ #include /** - * @fn InitMagTorquer + * @fn InitMagnetorquer * @brief Initialize functions for magnetometer without power port * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID @@ -17,10 +17,10 @@ * @param [in] component_step_time_s: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, - const GeomagneticField* geomagnetic_field); +Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, const std::string file_name, double component_step_time_s, + const GeomagneticField* geomagnetic_field); /** - * @fn InitMagTorquer + * @fn InitMagnetorquer * @brief Initialize functions for magnetometer with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port @@ -29,7 +29,7 @@ Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, int actuator_id, co * @param [in] component_step_time_s: Component step time [sec] * @param [in] geomagnetic_field: Geomegnetic environment */ -Magnetorquer InitMagTorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, - double component_step_time_s, const GeomagneticField* geomagnetic_field); +Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, const std::string file_name, + double component_step_time_s, const GeomagneticField* geomagnetic_field); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_MAGNETORQUER_HPP_ diff --git a/src/components/real/aocs/initialize_reaction_wheel.cpp b/src/components/real/aocs/initialize_reaction_wheel.cpp index 0281b38df..e3ae9d357 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.cpp +++ b/src/components/real/aocs/initialize_reaction_wheel.cpp @@ -98,7 +98,7 @@ void InitParams(int actuator_id, std::string file_name, double prop_step, double } } // namespace -ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { +ReactionWheel InitReactionWheel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); ReactionWheel rwmodel(prescaler, fast_prescaler, clock_generator, actuator_id, step_width_s, main_routine_time_step_s, jitter_update_interval_s, @@ -110,8 +110,8 @@ ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std: return rwmodel; } -ReactionWheel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, - double compo_update_step) { +ReactionWheel InitReactionWheel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, + double compo_update_step) { InitParams(actuator_id, file_name, prop_step, compo_update_step); power_port->InitializeWithInitializeFile(file_name); diff --git a/src/components/real/aocs/initialize_reaction_wheel.hpp b/src/components/real/aocs/initialize_reaction_wheel.hpp index 20b45caa1..2e00ef137 100644 --- a/src/components/real/aocs/initialize_reaction_wheel.hpp +++ b/src/components/real/aocs/initialize_reaction_wheel.hpp @@ -9,7 +9,7 @@ #include /** - * @fn InitRWModel + * @fn InitReactionWheel * @brief Initialize functions for reaction wheel without power port * @param [in] clock_generator: Clock generator * @param [in] actuator_id: Actuator ID @@ -17,9 +17,9 @@ * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step); +ReactionWheel InitReactionWheel(ClockGenerator* clock_generator, int actuator_id, std::string file_name, double prop_step, double compo_update_step); /** - * @fn InitRWModel + * @fn InitReactionWheel * @brief Initialize functions for reaction wheel with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port @@ -28,7 +28,7 @@ ReactionWheel InitRWModel(ClockGenerator* clock_generator, int actuator_id, std: * @param [in] prop_step: Propagation step for RW dynamics [sec] * @param [in] compo_update_step: Component step time [sec] */ -ReactionWheel InitRWModel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, - double compo_update_step); +ReactionWheel InitReactionWheel(ClockGenerator* clock_generator, PowerPort* power_port, int actuator_id, std::string file_name, double prop_step, + double compo_update_step); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_REACTION_WHEEL_HPP_ diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index 6b76f9294..4b86906c8 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -10,8 +10,8 @@ using namespace std; -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string file_name, double component_step_time_s, const Dynamics* dynamics, - const LocalEnvironment* local_environment) { +StarSensor InitStarSensor(ClockGenerator* clock_generator, int sensor_id, const string file_name, double component_step_time_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); @@ -43,8 +43,8 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const string return stt; } -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string file_name, double component_step_time_s, - const Dynamics* dynamics, const LocalEnvironment* local_environment) { +StarSensor InitStarSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const string file_name, double component_step_time_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment) { IniAccess STT_conf(file_name); const char* sensor_name = "STAR_SENSOR_"; const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); diff --git a/src/components/real/aocs/initialize_star_sensor.hpp b/src/components/real/aocs/initialize_star_sensor.hpp index 58f3d2bf7..6a3652d35 100644 --- a/src/components/real/aocs/initialize_star_sensor.hpp +++ b/src/components/real/aocs/initialize_star_sensor.hpp @@ -9,7 +9,7 @@ #include /** - * @fn InitSTT + * @fn InitStarSensor * @brief Initialize functions for StarSensor without power port * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID @@ -18,10 +18,10 @@ * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics, const LocalEnvironment* local_environment); +StarSensor InitStarSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, double component_step_time_s, + const Dynamics* dynamics, const LocalEnvironment* local_environment); /** - * @fn InitSTT + * @fn InitStarSensor * @brief Initialize functions for StarSensor with power port * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port @@ -31,7 +31,7 @@ StarSensor InitSTT(ClockGenerator* clock_generator, int sensor_id, const std::st * @param [in] dynamics: Dynamics information * @param [in] local_environment: Local environment information */ -StarSensor InitSTT(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, double component_step_time_s, - const Dynamics* dynamics, const LocalEnvironment* local_environment); +StarSensor InitStarSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, + double component_step_time_s, const Dynamics* dynamics, const LocalEnvironment* local_environment); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_STAR_SENSOR_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index da150c704..49e6acb1c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -17,7 +17,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // PCU power port connection pcu_ = new PCU(clock_gen); pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here - pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyro + pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyroSensor pcu_->ConnectPort(2, 1.0); // for other all components // Components @@ -27,19 +27,20 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // GyroSensor std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - gyro_ = new GyroSensor(InitGyro(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); + gyro_ = new GyroSensor( + InitGyroSensor(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // Magnetometer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_sensor_ = new Magnetometer(InitMagSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - &(local_env_->GetGeomagneticField()))); + mag_sensor_ = new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, + glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); // StarSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); stt_ = new StarSensor( - InitSTT(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); + InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); @@ -56,14 +57,14 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Magnetorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_torquer_ = new Magnetorquer(InitMagTorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, - glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); + mag_torquer_ = new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, + glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - rw_ = new ReactionWheel(InitRWModel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), - glo_env_->GetSimulationTime().GetComponentStepTime_s())); + rw_ = new ReactionWheel(InitReactionWheel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), + glo_env_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); From c9aaf614faf18c15d255c7688d3837567b43e01d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 10:57:15 +0100 Subject: [PATCH 0829/1086] Fix private variables name --- .../real/propulsion/simple_thruster.cpp | 50 +++++++++---------- .../real/propulsion/simple_thruster.hpp | 24 ++++----- 2 files changed, 37 insertions(+), 37 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 64cdcbee2..dc3db8e5f 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -14,10 +14,10 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), component_id_(component_id), - thruster_pos_b_(thruster_pos_b), - thrust_dir_b_(thrust_dir_b), - thrust_magnitude_max_(max_mag), - thrust_dir_err_(dir_err), + thruster_position_b_m_(thruster_pos_b), + thrust_direction_b_(thrust_dir_b), + thrust_magnitude_max_N_(max_mag), + direction_noise_standard_deviation_rad_(dir_err), structure_(structure), dynamics_(dynamics) { Initialize(mag_err, dir_err); @@ -28,10 +28,10 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera const double dir_err, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), component_id_(component_id), - thruster_pos_b_(thruster_pos_b), - thrust_dir_b_(thrust_dir_b), - thrust_magnitude_max_(max_mag), - thrust_dir_err_(dir_err), + thruster_position_b_m_(thruster_pos_b), + thrust_direction_b_(thrust_dir_b), + thrust_magnitude_max_N_(max_mag), + direction_noise_standard_deviation_rad_(dir_err), structure_(structure), dynamics_(dynamics) { Initialize(mag_err, dir_err); @@ -40,9 +40,9 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera SimpleThruster::~SimpleThruster() {} void SimpleThruster::Initialize(const double mag_err, const double dir_err) { - mag_nr_.SetParameters(0.0, mag_err); - dir_nr_.SetParameters(0.0, dir_err); - thrust_dir_b_ = Normalize(thrust_dir_b_); + magnitude_random_noise_.SetParameters(0.0, mag_err); + direction_random_noise_.SetParameters(0.0, dir_err); + thrust_direction_b_ = Normalize(thrust_direction_b_); } void SimpleThruster::MainRoutine(int count) { @@ -53,21 +53,21 @@ void SimpleThruster::MainRoutine(int count) { } void SimpleThruster::PowerOffRoutine() { - thrust_b_ *= 0.0; - torque_b_Nm_ *= 0.0; + output_thrust_b_N_ *= 0.0; + output_torque_b_Nm_ *= 0.0; } void SimpleThruster::CalcThrust() { double mag = CalcThrustMagnitude(); - if (duty_ > 0.0 + DBL_EPSILON) mag += mag_nr_; - thrust_b_ = mag * CalcThrustDir(); + if (duty_ > 0.0 + DBL_EPSILON) mag += magnitude_random_noise_; + output_thrust_b_N_ = mag * CalcThrustDir(); } void SimpleThruster::CalcTorque(Vector<3> center) { - Vector<3> vector_center2thruster = thruster_pos_b_ - center; - Vector<3> torque = OuterProduct(vector_center2thruster, thrust_b_); + Vector<3> vector_center2thruster = thruster_position_b_m_ - center; + Vector<3> torque = OuterProduct(vector_center2thruster, output_thrust_b_N_); - torque_b_Nm_ = torque; + output_torque_b_Nm_ = torque; } std::string SimpleThruster::GetLogHeader() const { @@ -83,18 +83,18 @@ std::string SimpleThruster::GetLogHeader() const { std::string SimpleThruster::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteVector(thrust_b_); - str_tmp += WriteVector(torque_b_Nm_); - str_tmp += WriteScalar(CalcNorm(thrust_b_)); + str_tmp += WriteVector(output_thrust_b_N_); + str_tmp += WriteVector(output_torque_b_Nm_); + str_tmp += WriteScalar(CalcNorm(output_thrust_b_N_)); return str_tmp; } -double SimpleThruster::CalcThrustMagnitude() { return duty_ * thrust_magnitude_max_; } +double SimpleThruster::CalcThrustMagnitude() { return duty_ * thrust_magnitude_max_N_; } Vector<3> SimpleThruster::CalcThrustDir() { - Vector<3> thrust_dir_b_true = thrust_dir_b_; - if (thrust_dir_err_ > 0.0 + DBL_EPSILON) { + Vector<3> thrust_dir_b_true = thrust_direction_b_; + if (direction_noise_standard_deviation_rad_ > 0.0 + DBL_EPSILON) { Vector<3> ex; // Fixme: to use outer product to generate orthogonal vector ex[0] = 1.0; ex[1] = 0.0; @@ -110,7 +110,7 @@ Vector<3> SimpleThruster::CalcThrustDir() { Quaternion make_axis_rot(thrust_dir_b_true, make_axis_rot_rad); Vector<3> axis_rot = make_axis_rot.FrameConversion(ex); - Quaternion err_rot(axis_rot, dir_nr_); // Generate error quaternion + Quaternion err_rot(axis_rot, direction_random_noise_); // Generate error quaternion thrust_dir_b_true = err_rot.FrameConversion(thrust_dir_b_true); // Add error } diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 36e5fa2d2..88695b0ac 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -91,12 +91,12 @@ class SimpleThruster : public Component, public ILoggable { * @fn GetThrustB * @brief Return generated thrust on the body fixed frame [N] */ - inline const Vector<3> GetThrustB() const { return thrust_b_; }; + inline const Vector<3> GetThrustB() const { return output_thrust_b_N_; }; /** * @fn GetTorqueB * @brief Return generated torque on the body fixed frame [Nm] */ - inline const Vector<3> GetTorqueB() const { return torque_b_Nm_; }; + inline const Vector<3> GetTorqueB() const { return output_torque_b_Nm_; }; // Setter /** @@ -107,17 +107,17 @@ class SimpleThruster : public Component, public ILoggable { protected: // parameters - const int component_id_; //!< Thruster ID - Vector<3> thruster_pos_b_{0.0}; //!< Thruster position @ body frame [m] - Vector<3> thrust_dir_b_{0.0}; //!< Thrust direction @ body frame - double duty_ = 0.0; //!< PWM Duty [0.0 : 1.0] - double thrust_magnitude_max_ = 0.0; //!< Maximum thrust magnitude [N] - double thrust_dir_err_ = 0.0; //!< Standard deviation of thrust direction error [rad] - libra::NormalRand mag_nr_; //!< Normal random for thrust magnitude error - libra::NormalRand dir_nr_; //!< Normal random for thrust direction error + const int component_id_; //!< Thruster ID + Vector<3> thruster_position_b_m_{0.0}; //!< Thruster position @ body frame [m] + Vector<3> thrust_direction_b_{0.0}; //!< Thrust direction @ body frame + 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 // outputs - Vector<3> thrust_b_{0.0}; //!< Generated thrust on the body fixed frame [N] - Vector<3> torque_b_Nm_{0.0}; //!< Generated torque on the body fixed frame [N] + 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] /** * @fn CalcThrust From 4cbcf5ae075b6431c825460cf753852bb61654c9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:02:59 +0100 Subject: [PATCH 0830/1086] Fix private function name --- .../propulsion/initialize_simple_thruster.cpp | 15 ++++----- .../real/propulsion/simple_thruster.cpp | 31 ++++++++++--------- .../real/propulsion/simple_thruster.hpp | 29 ++++++++--------- 3 files changed, 39 insertions(+), 36 deletions(-) diff --git a/src/components/real/propulsion/initialize_simple_thruster.cpp b/src/components/real/propulsion/initialize_simple_thruster.cpp index 745aef3ea..9297be926 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.cpp +++ b/src/components/real/propulsion/initialize_simple_thruster.cpp @@ -25,13 +25,14 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_ double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); - double mag_err; - mag_err = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); + double magnitude_standard_deviation_N; + magnitude_standard_deviation_N = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; - SimpleThruster thruster(prescaler, clock_generator, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, dynamics); + SimpleThruster thruster(prescaler, clock_generator, thruster_id, thruster_pos, thruster_dir, max_mag, magnitude_standard_deviation_N, deg_err, + structure, dynamics); return thruster; } @@ -52,15 +53,15 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* po double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); - double mag_err; - mag_err = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); + double magnitude_standard_deviation_N; + magnitude_standard_deviation_N = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; power_port->InitializeWithInitializeFile(file_name); - SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, mag_err, deg_err, structure, - dynamics); + SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, magnitude_standard_deviation_N, + deg_err, structure, dynamics); return thruster; } diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index dc3db8e5f..17451f24b 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -10,38 +10,39 @@ // Constructor SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, - const Structure* structure, const Dynamics* dynamics) + const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, + const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), component_id_(component_id), thruster_position_b_m_(thruster_pos_b), thrust_direction_b_(thrust_dir_b), thrust_magnitude_max_N_(max_mag), - direction_noise_standard_deviation_rad_(dir_err), + direction_noise_standard_deviation_rad_(direction_standard_deviation_N), structure_(structure), dynamics_(dynamics) { - Initialize(mag_err, dir_err); + Initialize(magnitude_standard_deviation_N, direction_standard_deviation_N); } SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, - const double dir_err, const Structure* structure, const Dynamics* dynamics) + const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, + const double magnitude_standard_deviation_N, const double direction_standard_deviation_N, const Structure* structure, + const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), component_id_(component_id), thruster_position_b_m_(thruster_pos_b), thrust_direction_b_(thrust_dir_b), thrust_magnitude_max_N_(max_mag), - direction_noise_standard_deviation_rad_(dir_err), + direction_noise_standard_deviation_rad_(direction_standard_deviation_N), structure_(structure), dynamics_(dynamics) { - Initialize(mag_err, dir_err); + Initialize(magnitude_standard_deviation_N, direction_standard_deviation_N); } SimpleThruster::~SimpleThruster() {} -void SimpleThruster::Initialize(const double mag_err, const double dir_err) { - magnitude_random_noise_.SetParameters(0.0, mag_err); - direction_random_noise_.SetParameters(0.0, dir_err); +void SimpleThruster::Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_N) { + magnitude_random_noise_.SetParameters(0.0, magnitude_standard_deviation_N); + direction_random_noise_.SetParameters(0.0, direction_standard_deviation_N); thrust_direction_b_ = Normalize(thrust_direction_b_); } @@ -60,11 +61,11 @@ void SimpleThruster::PowerOffRoutine() { void SimpleThruster::CalcThrust() { double mag = CalcThrustMagnitude(); if (duty_ > 0.0 + DBL_EPSILON) mag += magnitude_random_noise_; - output_thrust_b_N_ = mag * CalcThrustDir(); + output_thrust_b_N_ = mag * CalcThrustDirection(); } -void SimpleThruster::CalcTorque(Vector<3> center) { - Vector<3> vector_center2thruster = thruster_position_b_m_ - center; +void SimpleThruster::CalcTorque(const Vector<3> center_of_mass_b_m) { + Vector<3> vector_center2thruster = thruster_position_b_m_ - center_of_mass_b_m; Vector<3> torque = OuterProduct(vector_center2thruster, output_thrust_b_N_); output_torque_b_Nm_ = torque; @@ -92,7 +93,7 @@ std::string SimpleThruster::GetLogValue() const { double SimpleThruster::CalcThrustMagnitude() { return duty_ * thrust_magnitude_max_N_; } -Vector<3> SimpleThruster::CalcThrustDir() { +Vector<3> SimpleThruster::CalcThrustDirection() { Vector<3> thrust_dir_b_true = thrust_direction_b_; if (direction_noise_standard_deviation_rad_ > 0.0 + DBL_EPSILON) { Vector<3> ex; // Fixme: to use outer product to generate orthogonal vector diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 88695b0ac..7af0fd10f 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -30,14 +30,14 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame * @param [in] max_mag: Maximum thrust magnitude [N] - * @param [in] mag_err: Standard deviation of thrust magnitude error [N] - * @param [in] dir_err: Standard deviation of thrust direction error [rad] + * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] + * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, - const Dynamics* dynamics); + const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, + const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics); /** * @fn SimpleThruster * @brief Constructor with power port @@ -48,14 +48,14 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame * @param [in] max_mag: Maximum thrust magnitude [N] - * @param [in] mag_err: Standard deviation of thrust magnitude error [N] - * @param [in] dir_err: Standard deviation of thrust direction error [rad] + * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] + * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double mag_err, const double dir_err, const Structure* structure, - const Dynamics* dynamics); + const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, + const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics); /** * @fn ~SimpleThruster * @brief Destructor @@ -127,8 +127,9 @@ class SimpleThruster : public Component, public ILoggable { /** * @fn CalcTorque * @brief Calculate generated torque + * @param [in] center_of_mass_b_m: Center of mass position at body frame [m] */ - void CalcTorque(Vector<3> center); + void CalcTorque(const Vector<3> center_of_mass_b_m); /** * @fn CalcThrustMagnitude * @brief Calculate thrust magnitude @@ -136,18 +137,18 @@ class SimpleThruster : public Component, public ILoggable { */ double CalcThrustMagnitude(); /** - * @fn CalcThrustDir + * @fn CalcThrustDirection * @brief Calculate thrust direction * @return Thrust direction */ - Vector<3> CalcThrustDir(); + Vector<3> CalcThrustDirection(); /** * @fn Initialize * @brief Initialize function - * @param [in] mag_err: Standard deviation of thrust magnitude error [N] - * @param [in] dir_err: Standard deviation of thrust direction error [rad] + * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] + * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] */ - void Initialize(const double mag_err, const double dir_err); + void Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_N); const Structure* structure_; //!< Spacecraft structure information const Dynamics* dynamics_; //!< Spacecraft dynamics information From a82062134fb83927329e277ae361d17daf9b7005 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:04:13 +0100 Subject: [PATCH 0831/1086] Fix function arguments --- .../propulsion/initialize_simple_thruster.cpp | 12 +++---- .../real/propulsion/simple_thruster.cpp | 34 +++++++++---------- .../real/propulsion/simple_thruster.hpp | 33 +++++++++--------- 3 files changed, 40 insertions(+), 39 deletions(-) diff --git a/src/components/real/propulsion/initialize_simple_thruster.cpp b/src/components/real/propulsion/initialize_simple_thruster.cpp index 9297be926..2fc333a2f 100644 --- a/src/components/real/propulsion/initialize_simple_thruster.cpp +++ b/src/components/real/propulsion/initialize_simple_thruster.cpp @@ -23,7 +23,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_ Vector<3> thruster_dir; thruster_conf.ReadVector(Section, "thruster_direction_b", thruster_dir); - double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); + double max_magnitude_N = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); double magnitude_standard_deviation_N; magnitude_standard_deviation_N = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); @@ -31,8 +31,8 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, int thruster_ double deg_err; deg_err = thruster_conf.ReadDouble(Section, "direction_error_standard_deviation_deg") * libra::pi / 180.0; - SimpleThruster thruster(prescaler, clock_generator, thruster_id, thruster_pos, thruster_dir, max_mag, magnitude_standard_deviation_N, deg_err, - structure, dynamics); + SimpleThruster thruster(prescaler, clock_generator, thruster_id, thruster_pos, thruster_dir, max_magnitude_N, magnitude_standard_deviation_N, + deg_err, structure, dynamics); return thruster; } @@ -51,7 +51,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* po Vector<3> thruster_dir; thruster_conf.ReadVector(Section, "thruster_direction_b", thruster_dir); - double max_mag = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); + double max_magnitude_N = thruster_conf.ReadDouble(Section, "thrust_magnitude_N"); double magnitude_standard_deviation_N; magnitude_standard_deviation_N = thruster_conf.ReadDouble(Section, "thrust_error_standard_deviation_N"); @@ -61,7 +61,7 @@ SimpleThruster InitSimpleThruster(ClockGenerator* clock_generator, PowerPort* po power_port->InitializeWithInitializeFile(file_name); - SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_mag, magnitude_standard_deviation_N, - deg_err, structure, dynamics); + SimpleThruster thruster(prescaler, clock_generator, power_port, thruster_id, thruster_pos, thruster_dir, max_magnitude_N, + magnitude_standard_deviation_N, deg_err, structure, dynamics); return thruster; } diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 17451f24b..c51f454e9 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -9,40 +9,40 @@ #include // Constructor -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, - const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics) +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_position_b_m, + const Vector<3> thrust_dirction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, + const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), component_id_(component_id), - thruster_position_b_m_(thruster_pos_b), - thrust_direction_b_(thrust_dir_b), - thrust_magnitude_max_N_(max_mag), - direction_noise_standard_deviation_rad_(direction_standard_deviation_N), + thruster_position_b_m_(thruster_position_b_m), + thrust_direction_b_(thrust_dirction_b), + thrust_magnitude_max_N_(max_magnitude_N), + direction_noise_standard_deviation_rad_(direction_standard_deviation_rad), structure_(structure), dynamics_(dynamics) { - Initialize(magnitude_standard_deviation_N, direction_standard_deviation_N); + Initialize(magnitude_standard_deviation_N, direction_standard_deviation_rad); } SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Vector<3> thruster_pos_b, const Vector<3> thrust_dir_b, const double max_mag, - const double magnitude_standard_deviation_N, const double direction_standard_deviation_N, const Structure* structure, + const Vector<3> thruster_position_b_m, const Vector<3> thrust_dirction_b, const double max_magnitude_N, + const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), component_id_(component_id), - thruster_position_b_m_(thruster_pos_b), - thrust_direction_b_(thrust_dir_b), - thrust_magnitude_max_N_(max_mag), - direction_noise_standard_deviation_rad_(direction_standard_deviation_N), + thruster_position_b_m_(thruster_position_b_m), + thrust_direction_b_(thrust_dirction_b), + thrust_magnitude_max_N_(max_magnitude_N), + direction_noise_standard_deviation_rad_(direction_standard_deviation_rad), structure_(structure), dynamics_(dynamics) { - Initialize(magnitude_standard_deviation_N, direction_standard_deviation_N); + Initialize(magnitude_standard_deviation_N, direction_standard_deviation_rad); } SimpleThruster::~SimpleThruster() {} -void SimpleThruster::Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_N) { +void SimpleThruster::Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad) { magnitude_random_noise_.SetParameters(0.0, magnitude_standard_deviation_N); - direction_random_noise_.SetParameters(0.0, direction_standard_deviation_N); + direction_random_noise_.SetParameters(0.0, direction_standard_deviation_rad); thrust_direction_b_ = Normalize(thrust_direction_b_); } diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 7af0fd10f..bf6ce270a 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -27,17 +27,17 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] component_id: Thruster ID - * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] - * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame - * @param [in] max_mag: Maximum thrust magnitude [N] + * @param [in] thruster_position_b_m: Position of thruster on the body fixed frame [m] + * @param [in] thrust_dirction_b: Direction of thrust on the body fixed frame + * @param [in] max_magnitude_N: Maximum thrust magnitude [N] * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] - * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] + * @param [in] direction_standard_deviation_rad: Standard deviation of thrust direction error [rad] * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, - const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics); + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_position_b_m, + const Vector<3> thrust_dirction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, + const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics); /** * @fn SimpleThruster * @brief Constructor with power port @@ -45,17 +45,18 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] component_id: Thruster ID - * @param [in] thruster_pos_b: Position of thruster on the body fixed frame [m] - * @param [in] thrust_dir_b: Direction of thrust on the body fixed frame - * @param [in] max_mag: Maximum thrust magnitude [N] + * @param [in] thruster_position_b_m: Position of thruster on the body fixed frame [m] + * @param [in] thrust_dirction_b: Direction of thrust on the body fixed frame + * @param [in] max_magnitude_N: Maximum thrust magnitude [N] * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] - * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] + * @param [in] direction_standard_deviation_rad: Standard deviation of thrust direction error [rad] * @param [in] structure: Spacecraft structure information * @param [in] dynamics: Spacecraft dynamics information */ - SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const Vector<3> thruster_pos_b, - const Vector<3> thrust_dir_b, const double max_mag, const double magnitude_standard_deviation_N, - const double direction_standard_deviation_N, const Structure* structure, const Dynamics* dynamics); + SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, + const Vector<3> thruster_position_b_m, const Vector<3> thrust_dirction_b, const double max_magnitude_N, + const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, + const Dynamics* dynamics); /** * @fn ~SimpleThruster * @brief Destructor @@ -146,9 +147,9 @@ class SimpleThruster : public Component, public ILoggable { * @fn Initialize * @brief Initialize function * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] - * @param [in] direction_standard_deviation_N: Standard deviation of thrust direction error [rad] + * @param [in] direction_standard_deviation_rad: Standard deviation of thrust direction error [rad] */ - void Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_N); + void Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad); const Structure* structure_; //!< Spacecraft structure information const Dynamics* dynamics_; //!< Spacecraft dynamics information From f62eb4f8db1b5e7d0db7a6104b7aef50af575b97 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:04:33 +0100 Subject: [PATCH 0832/1086] Fix function arguments --- src/components/real/propulsion/simple_thruster.cpp | 8 ++++---- src/components/real/propulsion/simple_thruster.hpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index c51f454e9..8df8da1f7 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -10,12 +10,12 @@ // Constructor SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_position_b_m, - const Vector<3> thrust_dirction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, + const Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator), component_id_(component_id), thruster_position_b_m_(thruster_position_b_m), - thrust_direction_b_(thrust_dirction_b), + thrust_direction_b_(thrust_direction_b), thrust_magnitude_max_N_(max_magnitude_N), direction_noise_standard_deviation_rad_(direction_standard_deviation_rad), structure_(structure), @@ -24,13 +24,13 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera } SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Vector<3> thruster_position_b_m, const Vector<3> thrust_dirction_b, const double max_magnitude_N, + const Vector<3> thruster_position_b_m, const Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), component_id_(component_id), thruster_position_b_m_(thruster_position_b_m), - thrust_direction_b_(thrust_dirction_b), + thrust_direction_b_(thrust_direction_b), thrust_magnitude_max_N_(max_magnitude_N), direction_noise_standard_deviation_rad_(direction_standard_deviation_rad), structure_(structure), diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index bf6ce270a..08c783097 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -28,7 +28,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] component_id: Thruster ID * @param [in] thruster_position_b_m: Position of thruster on the body fixed frame [m] - * @param [in] thrust_dirction_b: Direction of thrust on the body fixed frame + * @param [in] thrust_direction_b: Direction of thrust on the body fixed frame * @param [in] max_magnitude_N: Maximum thrust magnitude [N] * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] * @param [in] direction_standard_deviation_rad: Standard deviation of thrust direction error [rad] @@ -36,7 +36,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] dynamics: Spacecraft dynamics information */ SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_position_b_m, - const Vector<3> thrust_dirction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, + const Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics); /** * @fn SimpleThruster @@ -46,7 +46,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] power_port: Power port * @param [in] component_id: Thruster ID * @param [in] thruster_position_b_m: Position of thruster on the body fixed frame [m] - * @param [in] thrust_dirction_b: Direction of thrust on the body fixed frame + * @param [in] thrust_direction_b: Direction of thrust on the body fixed frame * @param [in] max_magnitude_N: Maximum thrust magnitude [N] * @param [in] magnitude_standard_deviation_N: Standard deviation of thrust magnitude error [N] * @param [in] direction_standard_deviation_rad: Standard deviation of thrust direction error [rad] @@ -54,7 +54,7 @@ class SimpleThruster : public Component, public ILoggable { * @param [in] dynamics: Spacecraft dynamics information */ SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Vector<3> thruster_position_b_m, const Vector<3> thrust_dirction_b, const double max_magnitude_N, + const Vector<3> thruster_position_b_m, const Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics); /** From e10352da35f711d37276f8bf08606021acafd469 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:05:33 +0100 Subject: [PATCH 0833/1086] Fix public function name --- src/components/real/propulsion/simple_thruster.hpp | 8 ++++---- .../spacecraft/sample_spacecraft/sample_components.cpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 08c783097..5fddee2cf 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -89,15 +89,15 @@ class SimpleThruster : public Component, public ILoggable { // Getter /** - * @fn GetThrustB + * @fn GetOutputThrust_b_N * @brief Return generated thrust on the body fixed frame [N] */ - inline const Vector<3> GetThrustB() const { return output_thrust_b_N_; }; + inline const Vector<3> GetOutputThrust_b_N() const { return output_thrust_b_N_; }; /** - * @fn GetTorqueB + * @fn GetOutputTorque_b_Nm * @brief Return generated torque on the body fixed frame [Nm] */ - inline const Vector<3> GetTorqueB() const { return output_torque_b_Nm_; }; + inline const Vector<3> GetOutputTorque_b_Nm() const { return output_torque_b_Nm_; }; // Setter /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 49e6acb1c..0a0d0819e 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -152,7 +152,7 @@ SampleComponents::~SampleComponents() { libra::Vector<3> SampleComponents::GenerateForce_N_b() { libra::Vector<3> force_N_b_(0.0); - force_N_b_ += thruster_->GetThrustB(); + force_N_b_ += thruster_->GetOutputThrust_b_N(); force_N_b_ += force_generator_->GetGeneratedForce_b_N(); return force_N_b_; } @@ -161,7 +161,7 @@ libra::Vector<3> SampleComponents::GenerateTorque_Nm_b() { libra::Vector<3> torque_Nm_b_(0.0); torque_Nm_b_ += mag_torquer_->GetOutputTorque_b_Nm(); torque_Nm_b_ += rw_->GetOutputTorque_b_Nm(); - torque_Nm_b_ += thruster_->GetTorqueB(); + torque_Nm_b_ += thruster_->GetOutputTorque_b_Nm(); torque_Nm_b_ += torque_generator_->GetGeneratedTorque_b_Nm(); return torque_Nm_b_; } From f59b7e86773fbaa69f868f8ea44684de65387f8e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:06:14 +0100 Subject: [PATCH 0834/1086] Fix function arguments --- src/components/real/propulsion/simple_thruster.cpp | 4 ++-- src/components/real/propulsion/simple_thruster.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 8df8da1f7..cbefcff44 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -46,8 +46,8 @@ void SimpleThruster::Initialize(const double magnitude_standard_deviation_N, con thrust_direction_b_ = Normalize(thrust_direction_b_); } -void SimpleThruster::MainRoutine(int count) { - UNUSED(count); +void SimpleThruster::MainRoutine(const int time_count) { + UNUSED(time_count); CalcThrust(); CalcTorque(structure_->GetKinematicsParams().GetCGb()); diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 5fddee2cf..26b5f0588 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -68,7 +68,7 @@ class SimpleThruster : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int count); + void MainRoutine(const int time_count); /** * @fn PowerOffRoutine * @brief Power off routine to stop force generation From db9db95718532dde99391e72ee3c53195d48ec5b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:09:29 +0100 Subject: [PATCH 0835/1086] Fix private variables name --- src/components/real/mission/telescope.cpp | 84 +++++++++++------------ src/components/real/mission/telescope.hpp | 16 ++--- 2 files changed, 50 insertions(+), 50 deletions(-) diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index b5e25a93a..86ff01faf 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -43,14 +43,14 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern // Set 0 when t=0 for (size_t i = 0; i < num_of_logged_stars_; i++) { Star star; - star.hipdata.hipparcos_id = -1; - star.hipdata.visible_magnitude = -1; - star.hipdata.right_ascension_deg = -1; - star.hipdata.declination_deg = -1; - star.pos_imgsensor[0] = -1; - star.pos_imgsensor[1] = -1; - - star_in_sight.push_back(star); + star.hipparcos_data.hipparcos_id = -1; + star.hipparcos_data.visible_magnitude = -1; + star.hipparcos_data.right_ascension_deg = -1; + star.hipparcos_data.declination_deg = -1; + star.position_image_sensor[0] = -1; + star.position_image_sensor[1] = -1; + + star_list_in_sight.push_back(star); } } @@ -63,9 +63,9 @@ void Telescope::MainRoutine(int count) { is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_rad_); is_moon_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON"), moon_forbidden_angle_rad_); // Position calculation of celestial bodies from CelesInfo - Observe(sun_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN")); - Observe(earth_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH")); - Observe(moon_pos_imgsensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON")); + Observe(sun_position_image_sensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN")); + Observe(earth_position_image_sensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH")); + Observe(moon_position_image_sensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON")); // Position calculation of stars from Hipparcos Catalogue // No update when Hipparocos Catalogue was not readed if (hipp_->IsCalcEnabled) ObserveStars(); @@ -89,27 +89,27 @@ bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const doub return false; } -void Telescope::Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b) { +void Telescope::Observe(Vector<2>& position_image_sensor, const Vector<3, double> target_b) { Vector<3, double> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame if (abs(arg_x) < x_field_of_view_rad && abs(arg_y) < y_field_of_view_rad) { - pos_imgsensor[0] = x_num_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2; - pos_imgsensor[1] = y_num_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2; + position_image_sensor[0] = x_num_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2; + position_image_sensor[1] = y_num_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2; } else { // Return -1 when the body is in the out of FoV - pos_imgsensor[0] = -1; - pos_imgsensor[1] = -1; + position_image_sensor[0] = -1; + position_image_sensor[1] = -1; } } void Telescope::ObserveStars() { Quaternion quaternion_i2b = attitude_->GetQuaternion_i2b(); - star_in_sight.clear(); // Clear first - int count = 0; // Counter for while loop + star_list_in_sight.clear(); // Clear first + int count = 0; // Counter for while loop - while (star_in_sight.size() < num_of_logged_stars_) { + while (star_list_in_sight.size() < num_of_logged_stars_) { Vector<3> target_b = hipp_->GetStarDirection_b(count, quaternion_i2b); Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); @@ -118,30 +118,30 @@ void Telescope::ObserveStars() { if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { Star star; - star.hipdata.hipparcos_id = hipp_->GetHipparcosId(count); - star.hipdata.visible_magnitude = hipp_->GetVisibleMagnitude(count); - star.hipdata.right_ascension_deg = hipp_->GetRightAscension_deg(count); - star.hipdata.declination_deg = hipp_->GetDeclination_deg(count); - star.pos_imgsensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; - star.pos_imgsensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; - - star_in_sight.push_back(star); + star.hipparcos_data.hipparcos_id = hipp_->GetHipparcosId(count); + star.hipparcos_data.visible_magnitude = hipp_->GetVisibleMagnitude(count); + star.hipparcos_data.right_ascension_deg = hipp_->GetRightAscension_deg(count); + star.hipparcos_data.declination_deg = hipp_->GetDeclination_deg(count); + star.position_image_sensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; + star.position_image_sensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; + + star_list_in_sight.push_back(star); } count++; // If read all catalogue, fill -1 and break the loop if (count >= hipp_->GetCatalogueSize()) { - while (star_in_sight.size() < num_of_logged_stars_) { + while (star_list_in_sight.size() < num_of_logged_stars_) { Star star; - star.hipdata.hipparcos_id = -1; - star.hipdata.visible_magnitude = -1; - star.hipdata.right_ascension_deg = -1; - star.hipdata.declination_deg = -1; - star.pos_imgsensor[0] = -1; - star.pos_imgsensor[1] = -1; - - star_in_sight.push_back(star); + star.hipparcos_data.hipparcos_id = -1; + star.hipparcos_data.visible_magnitude = -1; + star.hipparcos_data.right_ascension_deg = -1; + star.hipparcos_data.declination_deg = -1; + star.position_image_sensor[0] = -1; + star.position_image_sensor[1] = -1; + + star_list_in_sight.push_back(star); } break; @@ -182,15 +182,15 @@ string Telescope::GetLogValue() const { str_tmp += WriteScalar(is_sun_in_forbidden_angle); str_tmp += WriteScalar(is_earth_in_forbidden_angle); str_tmp += WriteScalar(is_moon_in_forbidden_angle); - str_tmp += WriteVector(sun_pos_imgsensor); - str_tmp += WriteVector(earth_pos_imgsensor); - str_tmp += WriteVector(moon_pos_imgsensor); + str_tmp += WriteVector(sun_position_image_sensor); + str_tmp += WriteVector(earth_position_image_sensor); + str_tmp += WriteVector(moon_position_image_sensor); // When Hipparcos Catalogue was not read, no output of ObserveStars if (hipp_->IsCalcEnabled) { for (size_t i = 0; i < num_of_logged_stars_; i++) { - str_tmp += WriteScalar(star_in_sight[i].hipdata.hipparcos_id); - str_tmp += WriteScalar(star_in_sight[i].hipdata.visible_magnitude); - str_tmp += WriteVector(star_in_sight[i].pos_imgsensor); + str_tmp += WriteScalar(star_list_in_sight[i].hipparcos_data.hipparcos_id); + str_tmp += WriteScalar(star_list_in_sight[i].hipparcos_data.visible_magnitude); + str_tmp += WriteVector(star_list_in_sight[i].position_image_sensor); } } diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 36f9dc2db..7606b1388 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -20,8 +20,8 @@ * @brief Information of stars in the telescope's field of view */ struct Star { - HipparcosData hipdata; //!< Hipparcos data - libra::Vector<2> pos_imgsensor; //!< Position of image sensor + HipparcosData hipparcos_data; //!< Hipparcos data + libra::Vector<2> position_image_sensor; //!< Position of image sensor }; /* @@ -64,11 +64,11 @@ class Telescope : public Component, public ILoggable { size_t num_of_logged_stars_; //!< Number of logged stars - libra::Vector<2> sun_pos_imgsensor{-1}; //!< Position of the sun on the image plane - libra::Vector<2> earth_pos_imgsensor{-1}; //!< Position of the earth on the image plane - libra::Vector<2> moon_pos_imgsensor{-1}; //!< Position of the moon on the image plane + libra::Vector<2> sun_position_image_sensor{-1}; //!< Position of the sun on the image plane + libra::Vector<2> earth_position_image_sensor{-1}; //!< Position of the earth on the image plane + libra::Vector<2> moon_position_image_sensor{-1}; //!< Position of the moon on the image plane - std::vector star_in_sight; //!< Star information in the field of view + std::vector star_list_in_sight; //!< Star information in the field of view /** * @fn JudgeForbiddenAngle @@ -88,10 +88,10 @@ class Telescope : public Component, public ILoggable { /** * @fn Observe * @brief Convert body fixed direction vector to position on image sensor plane - * @param [out] pos_imgsensor: Position on image sensor plane + * @param [out] position_image_sensor: Position on image sensor plane * @param [in] target_b: Direction vector of target on the body fixed frame */ - void Observe(Vector<2>& pos_imgsensor, const Vector<3, double> target_b); + void Observe(Vector<2>& position_image_sensor, const Vector<3, double> target_b); /** * @fn ObserveStars * @brief Observe stars from Hipparcos catalogue From de368b74f7d70d354362a96489cfb5b9aa8e3a91 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:15:16 +0100 Subject: [PATCH 0836/1086] Add comments --- .../real/mission/initialize_telescope.cpp | 6 ++-- .../real/mission/initialize_telescope.hpp | 4 +-- src/components/real/mission/telescope.cpp | 10 +++---- src/components/real/mission/telescope.hpp | 30 +++++++++++++++---- 4 files changed, 35 insertions(+), 15 deletions(-) diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index a78a2f29c..115b30835 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -13,8 +13,8 @@ using namespace std; -Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string file_name, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celestial_information) { +Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const string file_name, const Attitude* attitude, + const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information) { using libra::pi; IniAccess Telescope_conf(file_name); @@ -49,6 +49,6 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); Telescope telescope(clock_generator, quaternion_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, - y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipp, local_celestial_information); + y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipparcos, local_celestial_information); return telescope; } diff --git a/src/components/real/mission/initialize_telescope.hpp b/src/components/real/mission/initialize_telescope.hpp index 152b28fa4..33b1f906b 100644 --- a/src/components/real/mission/initialize_telescope.hpp +++ b/src/components/real/mission/initialize_telescope.hpp @@ -15,10 +15,10 @@ * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to initialize file * @param [in] attitude: Attitude information - * @param [in] hipp: Star information by Hipparcos catalogue + * @param [in] hipparcos: Star information by Hipparcos catalogue * @param [in] local_celestial_information: Local celestial information */ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, const Attitude* attitude, - const HipparcosCatalogue* hipp, const LocalCelestialInformation* local_celestial_information); + const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_MISSION_INITIALIZE_TELESCOPE_HPP_ diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index 86ff01faf..fa074ff46 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -11,10 +11,10 @@ using namespace std; using namespace libra; -Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle_rad, - double earth_forbidden_angle_rad, double moon_forbidden_angle_rad, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, - double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celestial_information) +Telescope::Telescope(ClockGenerator* clock_generator, const libra::Quaternion& quaternion_b2c, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_num_of_pix, const int y_num_of_pix, + const double x_fov_par_pix, const double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, + const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information) : Component(1, clock_generator), quaternion_b2c_(quaternion_b2c), sun_forbidden_angle_rad_(sun_forbidden_angle_rad), @@ -26,7 +26,7 @@ Telescope::Telescope(ClockGenerator* clock_generator, libra::Quaternion& quatern y_fov_par_pix_(y_fov_par_pix), num_of_logged_stars_(num_of_logged_stars), attitude_(attitude), - hipp_(hipp), + hipp_(hipparcos), local_celestial_information_(local_celestial_information) { is_sun_in_forbidden_angle = true; is_earth_in_forbidden_angle = true; diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 7606b1388..d2da18564 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -30,11 +30,31 @@ struct Star { */ class Telescope : public Component, public ILoggable { public: - Telescope(ClockGenerator* clock_generator, libra::Quaternion& quaternion_b2c, double sun_forbidden_angle_rad, double earth_forbidden_angle_rad, - double moon_forbidden_angle_rad, int x_num_of_pix, int y_num_of_pix, double x_fov_par_pix, double y_fov_par_pix, - size_t num_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipp, - const LocalCelestialInformation* local_celestial_information); - + /** + * @fn Telescope + * @brief Constructor + * @param [in] clock_generator: Clock Generator + * @param [in] quaternion_b2c: Frame conversion Quaternion from body to component frame + * @param [in] sun_forbidden_angle_rad: Sun forbidden angle [rad] + * @param [in] earth_forbidden_angle_rad: Earth forbidden angle [rad] + * @param [in] moon_forbidden_angle_rad: Moon forbidden angle [rad] + * @param [in] x_num_of_pix: Number of pixel on X-axis in the image plane + * @param [in] y_num_of_pix: Number of pixel on Y-axis in the image plane + * @param [in] x_fov_par_pix: Field of view per pixel of X-axis in the image plane [rad/pix] + * @param [in] y_fov_par_pix: Field of view per pixel of Y-axis in the image plane [rad/pix] + * @param [in] num_of_logged_stars: Number of logged stars + * @param [in] attitude: Attitude Information + * @param [in] hipparcos: Hipparcos catalogue information + * @param [in] local_celestial_information: Local celestial information + */ + Telescope(ClockGenerator* clock_generator, const libra::Quaternion& quaternion_b2c, const double sun_forbidden_angle_rad, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_num_of_pix, const int y_num_of_pix, + const double x_fov_par_pix, const double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, + const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information); + /** + * @fn ~Telescope + * @brief Destructor + */ ~Telescope(); // Getter From 8c2bbc9b56faa717153e7a4eea7d953cc30b0e01 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:17:28 +0100 Subject: [PATCH 0837/1086] Fix private variables name --- .../real/mission/initialize_telescope.cpp | 19 +++--- src/components/real/mission/telescope.cpp | 58 +++++++++---------- src/components/real/mission/telescope.hpp | 26 ++++----- 3 files changed, 52 insertions(+), 51 deletions(-) diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index 115b30835..87ec27616 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -38,17 +38,18 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st double moon_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "moon_exclusion_angle_deg"); double moon_forbidden_angle_rad = moon_forbidden_angle_deg * pi / 180; // deg to rad - int x_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); - int y_num_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_number_of_pixel"); + int x_number_of_pix = Telescope_conf.ReadInt(TelescopeSection, "x_number_of_pixel"); + int y_number_of_pix = Telescope_conf.ReadInt(TelescopeSection, "y_number_of_pixel"); - double x_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_deg_per_pixel"); - double x_fov_par_pix_rad = x_fov_par_pix_deg * pi / 180; // deg to rad - double y_fov_par_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_deg_per_pixel"); - double y_fov_par_pix_rad = y_fov_par_pix_deg * pi / 180; // deg to rad + double x_fov_per_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "x_fov_deg_per_pixel"); + double x_fov_per_pix_rad = x_fov_per_pix_deg * pi / 180; // deg to rad + double y_fov_per_pix_deg = Telescope_conf.ReadDouble(TelescopeSection, "y_fov_deg_per_pixel"); + double y_fov_per_pix_rad = y_fov_per_pix_deg * pi / 180; // deg to rad - int num_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); + int number_of_logged_stars = Telescope_conf.ReadInt(TelescopeSection, "number_of_stars_for_log"); - Telescope telescope(clock_generator, quaternion_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_num_of_pix, - y_num_of_pix, x_fov_par_pix_rad, y_fov_par_pix_rad, num_of_logged_stars, attitude, hipparcos, local_celestial_information); + Telescope telescope(clock_generator, quaternion_b2c, sun_forbidden_angle_rad, earth_forbidden_angle_rad, moon_forbidden_angle_rad, x_number_of_pix, + y_number_of_pix, x_fov_per_pix_rad, y_fov_per_pix_rad, number_of_logged_stars, attitude, hipparcos, + local_celestial_information); return telescope; } diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index fa074ff46..fd63620fb 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -12,28 +12,28 @@ using namespace std; using namespace libra; Telescope::Telescope(ClockGenerator* clock_generator, const libra::Quaternion& quaternion_b2c, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_num_of_pix, const int y_num_of_pix, - const double x_fov_par_pix, const double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, - const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information) + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_number_of_pix, + const int y_number_of_pix, const double x_fov_per_pix, const double y_fov_per_pix, size_t number_of_logged_stars, + const Attitude* attitude, const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information) : Component(1, clock_generator), quaternion_b2c_(quaternion_b2c), sun_forbidden_angle_rad_(sun_forbidden_angle_rad), earth_forbidden_angle_rad_(earth_forbidden_angle_rad), moon_forbidden_angle_rad_(moon_forbidden_angle_rad), - x_num_of_pix_(x_num_of_pix), - y_num_of_pix_(y_num_of_pix), - x_fov_par_pix_(x_fov_par_pix), - y_fov_par_pix_(y_fov_par_pix), - num_of_logged_stars_(num_of_logged_stars), + x_number_of_pix_(x_number_of_pix), + y_number_of_pix_(y_number_of_pix), + x_fov_per_pix_(x_fov_per_pix), + y_fov_per_pix_(y_fov_per_pix), + number_of_logged_stars_(number_of_logged_stars), attitude_(attitude), - hipp_(hipparcos), + hipparcos_(hipparcos), local_celestial_information_(local_celestial_information) { is_sun_in_forbidden_angle = true; is_earth_in_forbidden_angle = true; is_moon_in_forbidden_angle = true; - x_field_of_view_rad = x_num_of_pix_ * x_fov_par_pix_; - y_field_of_view_rad = y_num_of_pix_ * y_fov_par_pix_; + x_field_of_view_rad = x_number_of_pix_ * x_fov_per_pix_; + y_field_of_view_rad = y_number_of_pix_ * y_fov_per_pix_; assert(x_field_of_view_rad < libra::pi_2); // Avoid the case that the field of view is over 90 degrees assert(y_field_of_view_rad < libra::pi_2); @@ -41,7 +41,7 @@ Telescope::Telescope(ClockGenerator* clock_generator, const libra::Quaternion& q sight_direction_c_[0] = 1; // (1,0,0) at component frame, Sight direction vector // Set 0 when t=0 - for (size_t i = 0; i < num_of_logged_stars_; i++) { + for (size_t i = 0; i < number_of_logged_stars_; i++) { Star star; star.hipparcos_data.hipparcos_id = -1; star.hipparcos_data.visible_magnitude = -1; @@ -68,7 +68,7 @@ void Telescope::MainRoutine(int count) { Observe(moon_position_image_sensor, local_celestial_information_->GetPositionFromSpacecraft_b_m("MOON")); // Position calculation of stars from Hipparcos Catalogue // No update when Hipparocos Catalogue was not readed - if (hipp_->IsCalcEnabled) ObserveStars(); + if (hipparcos_->IsCalcEnabled) ObserveStars(); // Debug ****************************************************************** // sun_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("SUN")); // earth_pos_c = quaternion_b2c_.FrameConversion(dynamics_->celestial_->GetPositionFromSpacecraft_b_m("EARTH")); @@ -95,8 +95,8 @@ void Telescope::Observe(Vector<2>& position_image_sensor, const Vector<3, double double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame if (abs(arg_x) < x_field_of_view_rad && abs(arg_y) < y_field_of_view_rad) { - position_image_sensor[0] = x_num_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2; - position_image_sensor[1] = y_num_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2; + position_image_sensor[0] = x_number_of_pix_ / 2 * tan(arg_x) / tan(x_field_of_view_rad) + x_number_of_pix_ / 2; + position_image_sensor[1] = y_number_of_pix_ / 2 * tan(arg_y) / tan(y_field_of_view_rad) + y_number_of_pix_ / 2; } else { // Return -1 when the body is in the out of FoV position_image_sensor[0] = -1; position_image_sensor[1] = -1; @@ -109,8 +109,8 @@ void Telescope::ObserveStars() { star_list_in_sight.clear(); // Clear first int count = 0; // Counter for while loop - while (star_list_in_sight.size() < num_of_logged_stars_) { - Vector<3> target_b = hipp_->GetStarDirection_b(count, quaternion_i2b); + while (star_list_in_sight.size() < number_of_logged_stars_) { + Vector<3> target_b = hipparcos_->GetStarDirection_b(count, quaternion_i2b); Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame @@ -118,12 +118,12 @@ void Telescope::ObserveStars() { if (abs(arg_x) <= x_field_of_view_rad && abs(arg_y) <= y_field_of_view_rad) { Star star; - star.hipparcos_data.hipparcos_id = hipp_->GetHipparcosId(count); - star.hipparcos_data.visible_magnitude = hipp_->GetVisibleMagnitude(count); - star.hipparcos_data.right_ascension_deg = hipp_->GetRightAscension_deg(count); - star.hipparcos_data.declination_deg = hipp_->GetDeclination_deg(count); - star.position_image_sensor[0] = x_num_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_num_of_pix_ / 2.0; - star.position_image_sensor[1] = y_num_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_num_of_pix_ / 2.0; + star.hipparcos_data.hipparcos_id = hipparcos_->GetHipparcosId(count); + star.hipparcos_data.visible_magnitude = hipparcos_->GetVisibleMagnitude(count); + star.hipparcos_data.right_ascension_deg = hipparcos_->GetRightAscension_deg(count); + star.hipparcos_data.declination_deg = hipparcos_->GetDeclination_deg(count); + star.position_image_sensor[0] = x_number_of_pix_ / 2.0 * tan(arg_x) / tan(x_field_of_view_rad) + x_number_of_pix_ / 2.0; + star.position_image_sensor[1] = y_number_of_pix_ / 2.0 * tan(arg_y) / tan(y_field_of_view_rad) + y_number_of_pix_ / 2.0; star_list_in_sight.push_back(star); } @@ -131,8 +131,8 @@ void Telescope::ObserveStars() { count++; // If read all catalogue, fill -1 and break the loop - if (count >= hipp_->GetCatalogueSize()) { - while (star_list_in_sight.size() < num_of_logged_stars_) { + if (count >= hipparcos_->GetCatalogueSize()) { + while (star_list_in_sight.size() < number_of_logged_stars_) { Star star; star.hipparcos_data.hipparcos_id = -1; star.hipparcos_data.visible_magnitude = -1; @@ -161,8 +161,8 @@ string Telescope::GetLogHeader() const { str_tmp += WriteVector(component_name + "earth_position", "img", "pix", 2); str_tmp += WriteVector(component_name + "moon_position", "img", "pix", 2); // When Hipparcos Catalogue was not read, no output of ObserveStars - if (hipp_->IsCalcEnabled) { - for (size_t i = 0; i < num_of_logged_stars_; i++) { + if (hipparcos_->IsCalcEnabled) { + for (size_t i = 0; i < number_of_logged_stars_; i++) { str_tmp += WriteScalar(component_name + "hipparcos_id (" + to_string(i) + ")", " "); str_tmp += WriteScalar(component_name + "visible_magnitude (" + to_string(i) + ")", " "); str_tmp += WriteVector(component_name + "star_position (" + to_string(i) + ")", "img", "pix", 2); @@ -186,8 +186,8 @@ string Telescope::GetLogValue() const { str_tmp += WriteVector(earth_position_image_sensor); str_tmp += WriteVector(moon_position_image_sensor); // When Hipparcos Catalogue was not read, no output of ObserveStars - if (hipp_->IsCalcEnabled) { - for (size_t i = 0; i < num_of_logged_stars_; i++) { + if (hipparcos_->IsCalcEnabled) { + for (size_t i = 0; i < number_of_logged_stars_; i++) { str_tmp += WriteScalar(star_list_in_sight[i].hipparcos_data.hipparcos_id); str_tmp += WriteScalar(star_list_in_sight[i].hipparcos_data.visible_magnitude); str_tmp += WriteVector(star_list_in_sight[i].position_image_sensor); diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index d2da18564..3f7a83d33 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -38,18 +38,18 @@ class Telescope : public Component, public ILoggable { * @param [in] sun_forbidden_angle_rad: Sun forbidden angle [rad] * @param [in] earth_forbidden_angle_rad: Earth forbidden angle [rad] * @param [in] moon_forbidden_angle_rad: Moon forbidden angle [rad] - * @param [in] x_num_of_pix: Number of pixel on X-axis in the image plane - * @param [in] y_num_of_pix: Number of pixel on Y-axis in the image plane - * @param [in] x_fov_par_pix: Field of view per pixel of X-axis in the image plane [rad/pix] - * @param [in] y_fov_par_pix: Field of view per pixel of Y-axis in the image plane [rad/pix] - * @param [in] num_of_logged_stars: Number of logged stars + * @param [in] x_number_of_pix: Number of pixel on X-axis in the image plane + * @param [in] y_number_of_pix: Number of pixel on Y-axis in the image plane + * @param [in] x_fov_per_pix: Field of view per pixel of X-axis in the image plane [rad/pix] + * @param [in] y_fov_per_pix: Field of view per pixel of Y-axis in the image plane [rad/pix] + * @param [in] number_of_logged_stars: Number of logged stars * @param [in] attitude: Attitude Information * @param [in] hipparcos: Hipparcos catalogue information * @param [in] local_celestial_information: Local celestial information */ Telescope(ClockGenerator* clock_generator, const libra::Quaternion& quaternion_b2c, const double sun_forbidden_angle_rad, - const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_num_of_pix, const int y_num_of_pix, - const double x_fov_par_pix, const double y_fov_par_pix, size_t num_of_logged_stars, const Attitude* attitude, + const double earth_forbidden_angle_rad, const double moon_forbidden_angle_rad, const int x_number_of_pix, const int y_number_of_pix, + const double x_fov_per_pix, const double y_fov_per_pix, size_t number_of_logged_stars, const Attitude* attitude, const HipparcosCatalogue* hipparcos, const LocalCelestialInformation* local_celestial_information); /** * @fn ~Telescope @@ -71,10 +71,10 @@ class Telescope : public Component, public ILoggable { double earth_forbidden_angle_rad_; //!< Earth forbidden angle [rad] double moon_forbidden_angle_rad_; //!< Moon forbidden angle [rad] - int x_num_of_pix_; //!< Number of pixel on X-axis in the image plane - int y_num_of_pix_; //!< Number of pixel on Y-axis in the image plane - double x_fov_par_pix_; //!< Field of view per pixel of X-axis in the image plane [rad/pix] - double y_fov_par_pix_; //!< Field of view per pixel of Y-axis in the image plane [rad/pix] + int x_number_of_pix_; //!< Number of pixel on X-axis in the image plane + int y_number_of_pix_; //!< Number of pixel on Y-axis in the image plane + double x_fov_per_pix_; //!< Field of view per pixel of X-axis in the image plane [rad/pix] + double y_fov_per_pix_; //!< Field of view per pixel of Y-axis in the image plane [rad/pix] double x_field_of_view_rad; //!< Field of view of X-axis in the image plane [rad/pix] double y_field_of_view_rad; //!< Field of view of Y-axis in the image plane [rad/pix] @@ -82,7 +82,7 @@ class Telescope : public Component, public ILoggable { bool is_earth_in_forbidden_angle = false; //!< Is the earth in the forbidden angle bool is_moon_in_forbidden_angle = false; //!< Is the moon in the forbidden angle - size_t num_of_logged_stars_; //!< Number of logged stars + size_t number_of_logged_stars_; //!< Number of logged stars libra::Vector<2> sun_position_image_sensor{-1}; //!< Position of the sun on the image plane libra::Vector<2> earth_position_image_sensor{-1}; //!< Position of the earth on the image plane @@ -119,7 +119,7 @@ class Telescope : public Component, public ILoggable { void ObserveStars(); const Attitude* attitude_; //!< Attitude information - const HipparcosCatalogue* hipp_; //!< Star information + const HipparcosCatalogue* hipparcos_; //!< Star information const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information // Override ILoggable From 32c13af92554491a1383fdac0d7b9121eaa7e93a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:18:46 +0100 Subject: [PATCH 0838/1086] Fix comments --- src/components/real/communication/antenna.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 98821dd0e..be69c7403 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -134,15 +134,15 @@ class Antenna { // Rx info double rx_system_noise_temperature_K_; //!< Receive system noise temperature [K] - AntennaParameters rx_params_; //!< Rx parameters + AntennaParameters rx_params_; //!< RX parameters double rx_gt_dBK_; //!< Receive G/T [dB/K] /** * @fn CalcAntennaGain * @brief Calculation antenna gain considering the target direction * @param [in] ant_params: Antenna parameters - * @param [in] theta: Angle from PZ axis on the antenna frame [rad] - * @param [in] phi: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) + * @param [in] theta_rad: Angle from PZ axis on the antenna frame [rad] + * @param [in] phi_rad: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return Antenna gain [dBi] */ double CalcAntennaGain(const AntennaParameters ant_params, const double theta_rad, const double phi_rad = 0.0) const; From 2ec2940405e62c8dff2092e4add53b8564da8fb1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:24:25 +0100 Subject: [PATCH 0839/1086] Fix private variables and arguments --- src/components/real/communication/antenna.cpp | 56 ++++++++++--------- src/components/real/communication/antenna.hpp | 40 ++++++------- .../ground_station_calculator.cpp | 12 ++-- .../real/communication/initialize_antenna.cpp | 56 +++++++++---------- 4 files changed, 83 insertions(+), 81 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 1f50ba0fe..43ca219dd 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -9,58 +9,58 @@ #include Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency, const Vector<4> tx_params, const Vector<4> rx_params) - : component_id_(component_id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_(frequency) { + const double frequency_MHz, const Vector<4> tx_parameters, const Vector<4> rx_parameters) + : component_id_(component_id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_MHz_(frequency_MHz) { quaternion_b2c_ = quaternion_b2c; // Parameters - tx_output_power_W_ = tx_params[0]; - tx_params_.gain_dBi_ = tx_params[1]; - tx_params_.loss_feeder_dB_ = tx_params[2]; - tx_params_.loss_pointing_dB_ = tx_params[3]; + tx_output_power_W_ = tx_parameters[0]; + tx_parameters_.gain_dBi_ = tx_parameters[1]; + tx_parameters_.loss_feeder_dB_ = tx_parameters[2]; + tx_parameters_.loss_pointing_dB_ = tx_parameters[3]; - rx_params_.gain_dBi_ = rx_params[0]; - rx_params_.loss_feeder_dB_ = rx_params[1]; - rx_params_.loss_pointing_dB_ = rx_params[2]; - rx_system_noise_temperature_K_ = rx_params[3]; + rx_parameters_.gain_dBi_ = rx_parameters[0]; + rx_parameters_.loss_feeder_dB_ = rx_parameters[1]; + rx_parameters_.loss_pointing_dB_ = rx_parameters[2]; + rx_system_noise_temperature_K_ = rx_parameters[3]; // Antenna gain - tx_params_.antenna_gain_model = AntennaGainModel::ISOTROPIC; - rx_params_.antenna_gain_model = AntennaGainModel::ISOTROPIC; + tx_parameters_.antenna_gain_model = AntennaGainModel::ISOTROPIC; + rx_parameters_.antenna_gain_model = AntennaGainModel::ISOTROPIC; // Calculate the EIRP or GT for the maximum gain if (is_transmitter_) { - tx_eirp_dBW_ = 10 * log10(tx_output_power_W_) + tx_params_.loss_feeder_dB_ + tx_params_.loss_pointing_dB_; + tx_eirp_dBW_ = 10 * log10(tx_output_power_W_) + tx_parameters_.loss_feeder_dB_ + tx_parameters_.loss_pointing_dB_; } else { tx_eirp_dBW_ = 0.0; } if (is_receiver_) { - rx_gt_dBK_ = rx_params_.loss_feeder_dB_ + rx_params_.loss_pointing_dB_ - 10 * std::log10(rx_system_noise_temperature_K_); + rx_gt_dBK_ = rx_parameters_.loss_feeder_dB_ + rx_parameters_.loss_pointing_dB_ - 10 * std::log10(rx_system_noise_temperature_K_); } else { rx_gt_dBK_ = 0.0; } } Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency, const double tx_output_power_W, const AntennaParameters tx_params, - const double rx_system_noise_temperature_K, const AntennaParameters rx_params) + const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, + const double rx_system_noise_temperature_K, const AntennaParameters rx_parameters) : component_id_(component_id), quaternion_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), - frequency_(frequency), + frequency_MHz_(frequency_MHz), tx_output_power_W_(tx_output_power_W), - tx_params_(tx_params), + tx_parameters_(tx_parameters), rx_system_noise_temperature_K_(rx_system_noise_temperature_K), - rx_params_(rx_params) { + rx_parameters_(rx_parameters) { // Calculate the EIRP or GT for the maximum gain if (is_transmitter_) { - tx_eirp_dBW_ = 10 * log10(tx_output_power_W_) + tx_params_.loss_feeder_dB_ + tx_params_.loss_pointing_dB_; + tx_eirp_dBW_ = 10 * log10(tx_output_power_W_) + tx_parameters_.loss_feeder_dB_ + tx_parameters_.loss_pointing_dB_; } else { tx_eirp_dBW_ = 0.0; } if (is_receiver_) { - rx_gt_dBK_ = rx_params_.loss_feeder_dB_ + rx_params_.loss_pointing_dB_ - 10 * std::log10(rx_system_noise_temperature_K_); + rx_gt_dBK_ = rx_parameters_.loss_feeder_dB_ + rx_parameters_.loss_pointing_dB_ - 10 * std::log10(rx_system_noise_temperature_K_); } else { rx_gt_dBK_ = 0.0; } @@ -68,14 +68,14 @@ Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c Antenna::~Antenna() {} -double Antenna::CalcAntennaGain(const AntennaParameters ant_params, const double theta_rad, const double phi_rad) const { +double Antenna::CalcAntennaGain(const AntennaParameters antenna_parameters, const double theta_rad, const double phi_rad) const { double gain_dBi = 0.0; - switch (ant_params.antenna_gain_model) { + switch (antenna_parameters.antenna_gain_model) { case AntennaGainModel::ISOTROPIC: - gain_dBi = ant_params.gain_dBi_; + gain_dBi = antenna_parameters.gain_dBi_; break; case AntennaGainModel::RADIATION_PATTERN_CSV: - gain_dBi = ant_params.radiation_pattern.GetGain_dBi(theta_rad, phi_rad); + gain_dBi = antenna_parameters.radiation_pattern.GetGain_dBi(theta_rad, phi_rad); break; default: break; @@ -84,9 +84,11 @@ double Antenna::CalcAntennaGain(const AntennaParameters ant_params, const double } double Antenna::CalcTxEIRP(const double theta_rad, const double phi_rad) const { - return tx_eirp_dBW_ + CalcAntennaGain(tx_params_, theta_rad, phi_rad); + return tx_eirp_dBW_ + CalcAntennaGain(tx_parameters_, theta_rad, phi_rad); +} +double Antenna::CalcRxGT(const double theta_rad, const double phi_rad) const { + return rx_gt_dBK_ + CalcAntennaGain(rx_parameters_, theta_rad, phi_rad); } -double Antenna::CalcRxGT(const double theta_rad, const double phi_rad) const { return rx_gt_dBK_ + CalcAntennaGain(rx_params_, theta_rad, phi_rad); } AntennaGainModel SetAntennaGainModel(const std::string gain_model_name) { if (gain_model_name == "ISOTROPIC") { diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index be69c7403..32892432a 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -50,12 +50,12 @@ class Antenna { * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not - * @param [in] frequency: Center Frequency [MHz] - * @param [in] tx_params: output, gain, loss_feeder, loss_pointing for TX - * @param [in] rx_params: gain, loss_feeder, loss_pointing, system_temperature for RX + * @param [in] frequency_MHz: Center Frequency [MHz] + * @param [in] tx_parameters: output, gain, loss_feeder, loss_pointing for TX + * @param [in] rx_parameters: gain, loss_feeder, loss_pointing, system_temperature for RX */ - Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, - const Vector<4> tx_params, const Vector<4> rx_params); + Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, + const double frequency_MHz, const Vector<4> tx_parameters, const Vector<4> rx_parameters); /** * @fn Antenna @@ -64,15 +64,15 @@ class Antenna { * @param [in] quaternion_b2c: Coordinate transform from body to component * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not - * @param [in] frequency: Center Frequency [MHz] + * @param [in] frequency_MHz: Center Frequency [MHz] * @param [in] tx_output_power_W: Transmit output power [W] - * @param [in] tx_params: TX antenna parameters + * @param [in] tx_parameters: TX antenna parameters * @param [in] rx_system_noise_temperature_K: Receive system noise temperature [K] - * @param [in] rx_params: RX antenna parameters + * @param [in] rx_parameters: RX antenna parameters */ - Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, const double frequency, - const double tx_output_power_W, const AntennaParameters tx_params, const double rx_system_noise_temperature_K, - const AntennaParameters rx_params); + Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, + const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, + const double rx_system_noise_temperature_K, const AntennaParameters rx_parameters); /** * @fn ~Antenna * @brief Destructor @@ -99,9 +99,9 @@ class Antenna { // Getter /** * @fn GetFrequency - * @brief Return frequency [MHz] + * @brief Return frequency_MHz [MHz] */ - inline double GetFrequency() const { return frequency_; } + inline double GetFrequency() const { return frequency_MHz_; } /** * @fn GetQuaternion_b2c * @brief Return quaternion from body to component @@ -125,27 +125,27 @@ class Antenna { Quaternion quaternion_b2c_; //!< Coordinate transform from body to component bool is_transmitter_; //!< Antenna for transmitter or not bool is_receiver_; //!< Antenna for receiver or not - double frequency_; //!< Center Frequency [MHz] + double frequency_MHz_; //!< Center Frequency [MHz] // Tx info - double tx_output_power_W_; //!< Transmit output power [W] - AntennaParameters tx_params_; //!< Tx parameters - double tx_eirp_dBW_; //!< Transmit EIRP(Equivalent Isotropic Radiated Power) [dBW] + double tx_output_power_W_; //!< Transmit output power [W] + AntennaParameters tx_parameters_; //!< Tx parameters + double tx_eirp_dBW_; //!< Transmit EIRP(Equivalent Isotropic Radiated Power) [dBW] // Rx info double rx_system_noise_temperature_K_; //!< Receive system noise temperature [K] - AntennaParameters rx_params_; //!< RX parameters + AntennaParameters rx_parameters_; //!< RX parameters double rx_gt_dBK_; //!< Receive G/T [dB/K] /** * @fn CalcAntennaGain * @brief Calculation antenna gain considering the target direction - * @param [in] ant_params: Antenna parameters + * @param [in] antenna_parameters: Antenna parameters * @param [in] theta_rad: Angle from PZ axis on the antenna frame [rad] * @param [in] phi_rad: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return Antenna gain [dBi] */ - double CalcAntennaGain(const AntennaParameters ant_params, const double theta_rad, const double phi_rad = 0.0) const; + double CalcAntennaGain(const AntennaParameters antenna_parameters, const double theta_rad, const double phi_rad = 0.0) const; }; AntennaGainModel SetAntennaGainModel(const std::string gain_model_name); diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 3e8975246..efd5a6187 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -75,20 +75,20 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ sc_to_gs_i = libra::Normalize(sc_to_gs_i); Quaternion q_i_to_sc_ant = sc_tx_ant.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); - double theta_on_sc_ant_rad = acos(gs_direction_on_sc_frame[2]); - double phi_on_sc_ant_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_ant_rad)); + double theta_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[2]); + double phi_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_antenna_rad)); // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); Quaternion q_ecef_to_gs_ant = gs_rx_ant.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); - double theta_on_gs_ant_rad = acos(sc_direction_on_gs_frame[2]); - double phi_on_gs_ant_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_ant_rad)); + double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); + double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = sc_tx_ant.CalcTxEIRP(theta_on_sc_ant_rad, phi_on_sc_ant_rad) + loss_space_dB + loss_polarization_ + loss_atmosphere_ + - loss_rainfall_ + loss_others_ + gs_rx_ant.CalcRxGT(theta_on_gs_ant_rad, phi_on_gs_ant_rad) - + double cn0_dBHz = sc_tx_ant.CalcTxEIRP(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_ + loss_atmosphere_ + + loss_rainfall_ + loss_others_ + gs_rx_ant.CalcRxGT(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } diff --git a/src/components/real/communication/initialize_antenna.cpp b/src/components/real/communication/initialize_antenna.cpp index e696771e6..2c9a9eaca 100644 --- a/src/components/real/communication/initialize_antenna.cpp +++ b/src/components/real/communication/initialize_antenna.cpp @@ -17,8 +17,8 @@ using libra::Vector; Antenna InitAntenna(const int antenna_id, const std::string file_name) { IniAccess antenna_conf(file_name); - const std::string st_ant_id = std::to_string(static_cast(antenna_id)); - const char *cs = st_ant_id.data(); + const std::string st_antenna_id = std::to_string(static_cast(antenna_id)); + const char *cs = st_antenna_id.data(); char Section[30] = "ANTENNA_"; strcat(Section, cs); @@ -28,51 +28,51 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { bool is_transmitter = antenna_conf.ReadBoolean(Section, "is_transmitter"); bool is_receiver = antenna_conf.ReadBoolean(Section, "is_receiver"); - double frequency = antenna_conf.ReadDouble(Section, "frequency_MHz"); + double frequency_MHz = antenna_conf.ReadDouble(Section, "frequency_MHz"); double tx_output_power_W = antenna_conf.ReadDouble(Section, "tx_output_W"); double rx_system_noise_temperature_K = antenna_conf.ReadDouble(Section, "rx_system_noise_temperature_K"); - AntennaParameters tx_params; + AntennaParameters tx_parameters; if (is_transmitter) { - tx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "tx_gain_dBi"); - tx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_feeder_dB"); - tx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_pointing_dB"); - tx_params.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "tx_antenna_gain_model")); + tx_parameters.gain_dBi_ = antenna_conf.ReadDouble(Section, "tx_gain_dBi"); + tx_parameters.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_feeder_dB"); + tx_parameters.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "tx_loss_pointing_dB"); + tx_parameters.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "tx_antenna_gain_model")); size_t length_theta = antenna_conf.ReadInt(Section, "tx_length_theta"); size_t length_phi = antenna_conf.ReadInt(Section, "tx_length_phi"); double theta_max_rad = antenna_conf.ReadDouble(Section, "tx_theta_max_rad"); double phi_max_rad = antenna_conf.ReadDouble(Section, "tx_phi_max_rad"); - tx_params.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "tx_antenna_radiation_pattern_file"), length_theta, - length_phi, theta_max_rad, phi_max_rad); + tx_parameters.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "tx_antenna_radiation_pattern_file"), length_theta, + length_phi, theta_max_rad, phi_max_rad); } else { - tx_params.gain_dBi_ = 0.0; - tx_params.loss_feeder_dB_ = 0.0; - tx_params.loss_pointing_dB_ = 0.0; - tx_params.antenna_gain_model = AntennaGainModel::ISOTROPIC; + tx_parameters.gain_dBi_ = 0.0; + tx_parameters.loss_feeder_dB_ = 0.0; + tx_parameters.loss_pointing_dB_ = 0.0; + tx_parameters.antenna_gain_model = AntennaGainModel::ISOTROPIC; } - AntennaParameters rx_params; + AntennaParameters rx_parameters; if (is_receiver) { - rx_params.gain_dBi_ = antenna_conf.ReadDouble(Section, "rx_gain_dBi"); - rx_params.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_feeder_dB"); - rx_params.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_pointing_dB"); - rx_params.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "rx_antenna_gain_model")); - rx_params.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "rx_antenna_radiation_pattern_file")); + rx_parameters.gain_dBi_ = antenna_conf.ReadDouble(Section, "rx_gain_dBi"); + rx_parameters.loss_feeder_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_feeder_dB"); + rx_parameters.loss_pointing_dB_ = antenna_conf.ReadDouble(Section, "rx_loss_pointing_dB"); + rx_parameters.antenna_gain_model = SetAntennaGainModel(antenna_conf.ReadString(Section, "rx_antenna_gain_model")); + rx_parameters.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "rx_antenna_radiation_pattern_file")); size_t length_theta = antenna_conf.ReadInt(Section, "rx_length_theta"); size_t length_phi = antenna_conf.ReadInt(Section, "rx_length_phi"); double theta_max_rad = antenna_conf.ReadDouble(Section, "rx_theta_max_rad"); double phi_max_rad = antenna_conf.ReadDouble(Section, "rx_phi_max_rad"); - rx_params.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "rx_antenna_radiation_pattern_file"), length_theta, - length_phi, theta_max_rad, phi_max_rad); + rx_parameters.radiation_pattern = AntennaRadiationPattern(antenna_conf.ReadString(Section, "rx_antenna_radiation_pattern_file"), length_theta, + length_phi, theta_max_rad, phi_max_rad); } else { - rx_params.gain_dBi_ = 0.0; - rx_params.loss_feeder_dB_ = 0.0; - rx_params.loss_pointing_dB_ = 0.0; - rx_params.antenna_gain_model = AntennaGainModel::ISOTROPIC; + rx_parameters.gain_dBi_ = 0.0; + rx_parameters.loss_feeder_dB_ = 0.0; + rx_parameters.loss_pointing_dB_ = 0.0; + rx_parameters.antenna_gain_model = AntennaGainModel::ISOTROPIC; } - Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency, tx_output_power_W, tx_params, rx_system_noise_temperature_K, - rx_params); + Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency_MHz, tx_output_power_W, tx_parameters, + rx_system_noise_temperature_K, rx_parameters); return antenna; } From ca8351b3e41045e43ec79de14dd7ff6a9a443903 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:25:30 +0100 Subject: [PATCH 0840/1086] Fix public function name --- src/components/real/communication/antenna.cpp | 4 ++-- src/components/real/communication/antenna.hpp | 12 ++++++------ .../real/communication/ground_station_calculator.cpp | 6 +++--- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 43ca219dd..0ce58fb2c 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -83,10 +83,10 @@ double Antenna::CalcAntennaGain(const AntennaParameters antenna_parameters, cons return gain_dBi; } -double Antenna::CalcTxEIRP(const double theta_rad, const double phi_rad) const { +double Antenna::CalcTxEIRP_dBW(const double theta_rad, const double phi_rad) const { return tx_eirp_dBW_ + CalcAntennaGain(tx_parameters_, theta_rad, phi_rad); } -double Antenna::CalcRxGT(const double theta_rad, const double phi_rad) const { +double Antenna::CalcRxGT_dB_K(const double theta_rad, const double phi_rad) const { return rx_gt_dBK_ + CalcAntennaGain(rx_parameters_, theta_rad, phi_rad); } diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 32892432a..dc66d03a1 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -80,28 +80,28 @@ class Antenna { ~Antenna(); /** - * @fn CalcTxEIRP + * @fn CalcTxEIRP_dBW * @brief Calculation of TX EIRP * @param [in] theta: Angle from PZ axis on the antenna frame [rad] * @param [in] phi: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return TX EIRP [dBW] */ - double CalcTxEIRP(const double theta_rad, const double phi_rad = 0.0) const; + double CalcTxEIRP_dBW(const double theta_rad, const double phi_rad = 0.0) const; /** - * @fn CalcRxGT + * @fn CalcRxGT_dB_K * @brief Calculation of RX G/T * @param [in] theta: Angle from PZ axis on the antenna frame [rad] * @param [in] phi: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return RX G/T [dB/K] */ - double CalcRxGT(const double theta_rad, const double phi_rad = 0.0) const; + double CalcRxGT_dB_K(const double theta_rad, const double phi_rad = 0.0) const; // Getter /** - * @fn GetFrequency + * @fn GetFrequency_MHz * @brief Return frequency_MHz [MHz] */ - inline double GetFrequency() const { return frequency_MHz_; } + inline double GetFrequency_MHz() const { return frequency_MHz_; } /** * @fn GetQuaternion_b2c * @brief Return quaternion from body to component diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index efd5a6187..43734c15c 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -68,7 +68,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetGSPosition_i(); double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; - double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / sc_tx_ant.GetFrequency() / 1000.0)); + double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / sc_tx_ant.GetFrequency_MHz() / 1000.0)); // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; @@ -87,8 +87,8 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = sc_tx_ant.CalcTxEIRP(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_ + loss_atmosphere_ + - loss_rainfall_ + loss_others_ + gs_rx_ant.CalcRxGT(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + double cn0_dBHz = sc_tx_ant.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_ + loss_atmosphere_ + + loss_rainfall_ + loss_others_ + gs_rx_ant.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } From 25da07ffc5b426cea54688dad1d47bd2ed9e431f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:26:15 +0100 Subject: [PATCH 0841/1086] Remove using --- .../real/communication/ground_station_calculator.hpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index df3bc8f28..10a88d0b7 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -16,9 +16,6 @@ #include #include -using libra::Matrix; -using libra::Vector; - /* * @class GScalculator * @brief Emulation of analysis and calculation for Ground Stations From cbb7c1fd2493516af8568e7d06997dc5a6c14ff9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:26:53 +0100 Subject: [PATCH 0842/1086] Remove unnecessary include files --- .../real/communication/ground_station_calculator.hpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index 10a88d0b7..fc5cddea4 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -11,9 +11,6 @@ #include #include #include -#include -#include -#include #include /* From 852ae55c6aa2857520578a73c26d25a319891e83 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:29:09 +0100 Subject: [PATCH 0843/1086] Fix private variables --- .../ground_station_calculator.cpp | 26 +++++++++---------- .../ground_station_calculator.hpp | 18 ++++++------- .../initialize_ground_station_calculator.cpp | 12 ++++----- 3 files changed, 28 insertions(+), 28 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 43734c15c..3fa76bfbb 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -11,14 +11,14 @@ GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, const double EbN0, const double hardware_deterioration, const double coding_gain, const double margin_req, const double downlink_bitrate_bps) - : loss_polarization_(loss_polarization), - loss_atmosphere_(loss_atmosphere), - loss_rainfall_(loss_rainfall), - loss_others_(loss_others), - EbN0_(EbN0), - hardware_deterioration_(hardware_deterioration), - coding_gain_(coding_gain), - margin_req_(margin_req), + : loss_polarization_dB_(loss_polarization), + loss_atmosphere_dB_(loss_atmosphere), + loss_rainfall_dB_(loss_rainfall), + loss_others_dB_(loss_others), + ebn0_dB_(EbN0), + hardware_deterioration_dB_(hardware_deterioration), + coding_gain_dB_(coding_gain), + margin_requirement_dB_(margin_req), downlink_bitrate_bps_(downlink_bitrate_bps) { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -42,7 +42,7 @@ double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& sc_ const Antenna& gs_rx_ant) { double cn0_dBHz = CalcCn0OnGs(dynamics, sc_tx_ant, ground_station, gs_rx_ant); - double margin_for_bitrate_dB = cn0_dBHz - (EbN0_ + hardware_deterioration_ + coding_gain_) - margin_req_; + double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_) - margin_requirement_dB_; if (margin_for_bitrate_dB > 0) { return pow(10.0, margin_for_bitrate_dB / 10.0) / 1000000.0; @@ -54,7 +54,7 @@ double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& sc_ double GScalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant) { double cn0_dB = CalcCn0OnGs(dynamics, sc_tx_ant, ground_station, gs_rx_ant); - double cn0_requirement_dB = EbN0_ + hardware_deterioration_ + coding_gain_ + 10.0 * log10(downlink_bitrate_bps_); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(downlink_bitrate_bps_); return cn0_dB - cn0_requirement_dB; } @@ -87,9 +87,9 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = sc_tx_ant.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_ + loss_atmosphere_ + - loss_rainfall_ + loss_others_ + gs_rx_ant.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - - 10.0 * log10(environment::boltzmann_constant_J_K); + double cn0_dBHz = sc_tx_ant.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + + gs_rx_ant.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index fc5cddea4..89bde73b0 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -84,16 +84,16 @@ class GScalculator : public ILoggable { protected: // Parameters - double loss_polarization_; //!< Loss polarization [dB] - double loss_atmosphere_; //!< Loss atmosphere [dB] - double loss_rainfall_; //!< Loss rainfall [dB] - double loss_others_; //!< Loss others [dB] - double EbN0_; //!< EbN0 [dB] - double hardware_deterioration_; //!< Hardware deterioration [dB] - double coding_gain_; //!< Coding gain [dB] + double loss_polarization_dB_; //!< Loss polarization [dB] + double loss_atmosphere_dB_; //!< Loss atmosphere [dB] + double loss_rainfall_dB_; //!< Loss rainfall [dB] + double loss_others_dB_; //!< Loss others [dB] + double ebn0_dB_; //!< EbN0 [dB] + double hardware_deterioration_dB_; //!< Hardware deterioration [dB] + double coding_gain_dB_; //!< Coding gain [dB] // Variables - double margin_req_; //!< Required margin to calculate max bitrate [dB] - double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] + double margin_requirement_dB_; //!< Required margin to calculate max bitrate [dB] + double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] // Calculated values double receive_margin_dB_; //!< Receive margin [dB] diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index b015afb5c..4b005eeca 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -15,13 +15,13 @@ GScalculator InitGScalculator(const std::string file_name) { char Section[30] = "GROUND_STATION_CALCULATOR"; - double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization_dB"); - double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere_dB"); - double loss_rainfall = gs_conf.ReadDouble(Section, "loss_rainfall_dB"); - double loss_others = gs_conf.ReadDouble(Section, "loss_others_dB"); + double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB"); + double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB"); + double loss_rainfall = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB"); + double loss_others = gs_conf.ReadDouble(Section, "loss_others_dB_dB"); double EbN0 = gs_conf.ReadDouble(Section, "ebn0_dB"); - double hardware_deterioration = gs_conf.ReadDouble(Section, "hardware_deterioration_dB"); - double coding_gain = gs_conf.ReadDouble(Section, "coding_gain_dB"); + double hardware_deterioration = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB"); + double coding_gain = gs_conf.ReadDouble(Section, "coding_gain_dB_dB"); double margin_req = gs_conf.ReadDouble(Section, "margin_requirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); From 54f382bc9bc7a9fa27b50683c5c3ed11260506e2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:32:41 +0100 Subject: [PATCH 0844/1086] Fix function argument name --- .../ground_station_calculator.cpp | 63 ++++++++--------- .../ground_station_calculator.hpp | 67 ++++++++++--------- .../initialize_ground_station_calculator.cpp | 20 +++--- 3 files changed, 79 insertions(+), 71 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 3fa76bfbb..fccbf6066 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -8,17 +8,17 @@ #include #include -GScalculator::GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, - const double EbN0, const double hardware_deterioration, const double coding_gain, const double margin_req, - const double downlink_bitrate_bps) - : loss_polarization_dB_(loss_polarization), - loss_atmosphere_dB_(loss_atmosphere), - loss_rainfall_dB_(loss_rainfall), - loss_others_dB_(loss_others), - ebn0_dB_(EbN0), - hardware_deterioration_dB_(hardware_deterioration), - coding_gain_dB_(coding_gain), - margin_requirement_dB_(margin_req), +GScalculator::GScalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, + const double loss_others_dB, const double ebn0_dB, const double hardware_deterioration_dB, const double coding_gain_dB, + const double margin_requirement_dB, const double downlink_bitrate_bps) + : loss_polarization_dB_dB_(loss_polarization_dB), + loss_atmosphere_dB_dB_(loss_atmosphere_dB), + loss_rainfall_dB_dB_(loss_rainfall_dB), + loss_others_dB_dB_(loss_others_dB), + ebn0_dB_(ebn0_dB), + hardware_deterioration_dB_dB_(hardware_deterioration_dB), + coding_gain_dB_dB_(coding_gain_dB), + margin_requirement_dBuirement_dB_(margin_requirement_dB), downlink_bitrate_bps_(downlink_bitrate_bps) { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -26,11 +26,12 @@ GScalculator::GScalculator(const double loss_polarization, const double loss_atm GScalculator::~GScalculator() {} -void GScalculator::Update(const Spacecraft& spacecraft, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant) { +void GScalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { bool is_visible = ground_station.IsVisible(spacecraft.GetSatID()); if (is_visible) { - max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), sc_tx_ant, ground_station, gs_rx_ant); - receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), sc_tx_ant, ground_station, gs_rx_ant); + max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); + receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); } else { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -38,11 +39,11 @@ void GScalculator::Update(const Spacecraft& spacecraft, const Antenna& sc_tx_ant } // Private functions -double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, - const Antenna& gs_rx_ant) { - double cn0_dBHz = CalcCn0OnGs(dynamics, sc_tx_ant, ground_station, gs_rx_ant); +double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { + double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); - double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_) - margin_requirement_dB_; + double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_) - margin_requirement_dBuirement_dB_; if (margin_for_bitrate_dB > 0) { return pow(10.0, margin_for_bitrate_dB / 10.0) / 1000000.0; @@ -51,15 +52,16 @@ double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& sc_ } } -double GScalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, - const Antenna& gs_rx_ant) { - double cn0_dB = CalcCn0OnGs(dynamics, sc_tx_ant, ground_station, gs_rx_ant); - double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(downlink_bitrate_bps_); +double GScalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { + double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_ + 10.0 * log10(downlink_bitrate_bps_); return cn0_dB - cn0_requirement_dB; } -double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant) { - if (!sc_tx_ant.IsTransmitter() || !gs_rx_ant.IsReceiver()) { +double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { + if (!spacecraft_tx_antenna.IsTransmitter() || !ground_station_rx_antenna.IsReceiver()) { // Check compatibility of transmitter and receiver return 0.0f; } @@ -68,12 +70,12 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetGSPosition_i(); double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; - double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / sc_tx_ant.GetFrequency_MHz() / 1000.0)); + double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_tx_antenna.GetFrequency_MHz() / 1000.0)); // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; sc_to_gs_i = libra::Normalize(sc_to_gs_i); - Quaternion q_i_to_sc_ant = sc_tx_ant.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); + Quaternion q_i_to_sc_ant = spacecraft_tx_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[2]); double phi_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_antenna_rad)); @@ -81,15 +83,16 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); - Quaternion q_ecef_to_gs_ant = gs_rx_ant.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); + Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = sc_tx_ant.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + - loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - gs_rx_ant.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); + double cn0_dBHz = spacecraft_tx_antenna.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_dB_ + + loss_atmosphere_dB_dB_ + loss_rainfall_dB_dB_ + loss_others_dB_dB_ + + ground_station_rx_antenna.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index 89bde73b0..6ab47ea97 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -22,18 +22,19 @@ class GScalculator : public ILoggable { /** * @fn GScalculator * @brief Constructor - * @param [in] loss_polarization: Loss polarization [dB] - * @param [in] loss_atmosphere: Loss atmosphere [dB] - * @param [in] loss_rainfall: Loss rainfall [dB] - * @param [in] loss_others: Loss others [dB] - * @param [in] EbN0: EbN0 [dB] - * @param [in] hardware_deterioration: Hardware deterioration [dB] - * @param [in] coding_gain: Coding gain [dB] - * @param [in] margin_req: Required margin to calculate max bitrate [dB] + * @param [in] loss_polarization_dB: Loss polarization [dB] + * @param [in] loss_atmosphere_dB: Loss atmosphere [dB] + * @param [in] loss_rainfall_dB: Loss rainfall [dB] + * @param [in] loss_others_dB: Loss others [dB] + * @param [in] ebn0_dB: ebn0_dB [dB] + * @param [in] hardware_deterioration_dB: Hardware deterioration [dB] + * @param [in] coding_gain_dB: Coding gain [dB] + * @param [in] margin_requirement_dB: Required margin to calculate max bitrate [dB] * @param [in] downlink_bitrate_bps: Downlink bitrate to calculate receive margin [bps] */ - GScalculator(const double loss_polarization, const double loss_atmosphere, const double loss_rainfall, const double loss_others, const double EbN0, - const double hardware_deterioration, const double coding_gain, const double margin_req, const double downlink_bitrate_bps = 1000); + GScalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, const double loss_others_dB, + const double EbN0, const double hardware_deterioration_dB, const double coding_gain_dB, const double margin_requirement_dB, + const double downlink_bitrate_bps = 1000); /** * @fn ~GScalculator * @brief Destructor @@ -45,11 +46,12 @@ class GScalculator : public ILoggable { * @brief Update maximum bitrate calculation * @note TODO: fix function name * @param [in] spacecraft: Spacecraft information - * @param [in] sc_tx_ant: Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] gs_rx_ant: Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Antenna mounted on ground station */ - void Update(const Spacecraft& spacecraft, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); + void Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); // Override ILoggable TODO: Maybe we don't need logabble, and this class should be used as library. /** @@ -84,16 +86,16 @@ class GScalculator : public ILoggable { protected: // Parameters - double loss_polarization_dB_; //!< Loss polarization [dB] - double loss_atmosphere_dB_; //!< Loss atmosphere [dB] - double loss_rainfall_dB_; //!< Loss rainfall [dB] - double loss_others_dB_; //!< Loss others [dB] - double ebn0_dB_; //!< EbN0 [dB] - double hardware_deterioration_dB_; //!< Hardware deterioration [dB] - double coding_gain_dB_; //!< Coding gain [dB] + double loss_polarization_dB_dB_; //!< Loss polarization [dB] + double loss_atmosphere_dB_dB_; //!< Loss atmosphere [dB] + double loss_rainfall_dB_dB_; //!< Loss rainfall [dB] + double loss_others_dB_dB_; //!< Loss others [dB] + double ebn0_dB_; //!< EbN0 [dB] + double hardware_deterioration_dB_dB_; //!< Hardware deterioration [dB] + double coding_gain_dB_dB_; //!< Coding gain [dB] // Variables - double margin_requirement_dB_; //!< Required margin to calculate max bitrate [dB] - double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] + double margin_requirement_dBuirement_dB_; //!< Required margin to calculate max bitrate [dB] + double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] // Calculated values double receive_margin_dB_; //!< Receive margin [dB] @@ -103,33 +105,36 @@ class GScalculator : public ILoggable { * @fn CalcMaxBitrate * @brief Calculate the maximum bitrate * @param [in] dynamics: Spacecraft dynamics information - * @param [in] sc_tx_ant: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] gs_rx_ant: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return Max bitrate [Mbps] */ - double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); + double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); /** * @fn CalcReceiveMarginOnGs * @brief Calculate receive margin at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] sc_tx_ant: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] gs_rx_ant: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return Receive margin [dB] */ - double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); + double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); /** * @fn CalcCn0 * @brief Calculate CN0 (Carrier to Noise density ratio) of received signal at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] sc_tx_ant: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] gs_rx_ant: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return CN0 [dB] */ - double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& sc_tx_ant, const GroundStation& ground_station, const Antenna& gs_rx_ant); + double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); }; #endif // S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index 4b005eeca..0770412ee 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -15,17 +15,17 @@ GScalculator InitGScalculator(const std::string file_name) { char Section[30] = "GROUND_STATION_CALCULATOR"; - double loss_polarization = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB"); - double loss_atmosphere = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB"); - double loss_rainfall = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB"); - double loss_others = gs_conf.ReadDouble(Section, "loss_others_dB_dB"); - double EbN0 = gs_conf.ReadDouble(Section, "ebn0_dB"); - double hardware_deterioration = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB"); - double coding_gain = gs_conf.ReadDouble(Section, "coding_gain_dB_dB"); - double margin_req = gs_conf.ReadDouble(Section, "margin_requirement_dB"); + double loss_polarization_dB = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB_dB"); + double loss_atmosphere_dB = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB_dB"); + double loss_rainfall_dB = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB_dB"); + double loss_others_dB = gs_conf.ReadDouble(Section, "loss_others_dB_dB_dB"); + double ebn0_dB = gs_conf.ReadDouble(Section, "ebn0_dB"); + double hardware_deterioration_dB = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB_dB"); + double coding_gain_dB = gs_conf.ReadDouble(Section, "coding_gain_dB_dB_dB"); + double margin_requirement_dB = gs_conf.ReadDouble(Section, "margin_requirement_dBuirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); - GScalculator gs_calculator(loss_polarization, loss_atmosphere, loss_rainfall, loss_others, EbN0, hardware_deterioration, coding_gain, margin_req, - downlink_bitrate_bps); + GScalculator gs_calculator(loss_polarization_dB, loss_atmosphere_dB, loss_rainfall_dB, loss_others_dB, ebn0_dB, hardware_deterioration_dB, + coding_gain_dB, margin_requirement_dB, downlink_bitrate_bps); return gs_calculator; } From 9fbadf35401f4e64ba35006685ea716c95728020 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:35:00 +0100 Subject: [PATCH 0845/1086] Fix public function name --- .../ground_station_calculator.cpp | 28 +++++++++---------- .../ground_station_calculator.hpp | 17 ++++++----- .../initialize_ground_station_calculator.cpp | 6 ++-- .../initialize_ground_station_calculator.hpp | 2 +- .../sample_ground_station_components.cpp | 2 +- .../sample_ground_station_components.hpp | 8 +++--- 6 files changed, 31 insertions(+), 32 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index fccbf6066..bff0eab93 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -8,9 +8,9 @@ #include #include -GScalculator::GScalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, - const double loss_others_dB, const double ebn0_dB, const double hardware_deterioration_dB, const double coding_gain_dB, - const double margin_requirement_dB, const double downlink_bitrate_bps) +GroundStationCalculator::GroundStationCalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, + const double loss_others_dB, const double ebn0_dB, const double hardware_deterioration_dB, + const double coding_gain_dB, const double margin_requirement_dB, const double downlink_bitrate_bps) : loss_polarization_dB_dB_(loss_polarization_dB), loss_atmosphere_dB_dB_(loss_atmosphere_dB), loss_rainfall_dB_dB_(loss_rainfall_dB), @@ -24,10 +24,10 @@ GScalculator::GScalculator(const double loss_polarization_dB, const double loss_ receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? } -GScalculator::~GScalculator() {} +GroundStationCalculator::~GroundStationCalculator() {} -void GScalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { +void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { bool is_visible = ground_station.IsVisible(spacecraft.GetSatID()); if (is_visible) { max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); @@ -39,8 +39,8 @@ void GScalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraf } // Private functions -double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { +double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_) - margin_requirement_dBuirement_dB_; @@ -52,15 +52,15 @@ double GScalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spa } } -double GScalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { +double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, + const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_ + 10.0 * log10(downlink_bitrate_bps_); return cn0_dB - cn0_requirement_dB; } -double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { +double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { if (!spacecraft_tx_antenna.IsTransmitter() || !ground_station_rx_antenna.IsReceiver()) { // Check compatibility of transmitter and receiver return 0.0f; @@ -96,7 +96,7 @@ double GScalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacec return cn0_dBHz; } -std::string GScalculator::GetLogHeader() const { +std::string GroundStationCalculator::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "gs_calculator_"; @@ -106,7 +106,7 @@ std::string GScalculator::GetLogHeader() const { return str_tmp; } -std::string GScalculator::GetLogValue() const { +std::string GroundStationCalculator::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(max_bitrate_Mbps_); diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index 6ab47ea97..30c11db0b 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -14,13 +14,13 @@ #include /* - * @class GScalculator + * @class GroundStationCalculator * @brief Emulation of analysis and calculation for Ground Stations */ -class GScalculator : public ILoggable { +class GroundStationCalculator : public ILoggable { public: /** - * @fn GScalculator + * @fn GroundStationCalculator * @brief Constructor * @param [in] loss_polarization_dB: Loss polarization [dB] * @param [in] loss_atmosphere_dB: Loss atmosphere [dB] @@ -32,19 +32,18 @@ class GScalculator : public ILoggable { * @param [in] margin_requirement_dB: Required margin to calculate max bitrate [dB] * @param [in] downlink_bitrate_bps: Downlink bitrate to calculate receive margin [bps] */ - GScalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, const double loss_others_dB, - const double EbN0, const double hardware_deterioration_dB, const double coding_gain_dB, const double margin_requirement_dB, - const double downlink_bitrate_bps = 1000); + GroundStationCalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, + const double loss_others_dB, const double EbN0, const double hardware_deterioration_dB, const double coding_gain_dB, + const double margin_requirement_dB, const double downlink_bitrate_bps = 1000); /** - * @fn ~GScalculator + * @fn ~GroundStationCalculator * @brief Destructor */ - virtual ~GScalculator(); + virtual ~GroundStationCalculator(); /** * @fn Update * @brief Update maximum bitrate calculation - * @note TODO: fix function name * @param [in] spacecraft: Spacecraft information * @param [in] spacecraft_tx_antenna: Antenna mounted on spacecraft * @param [in] ground_station: Ground station information diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index 0770412ee..0d4056b60 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -GScalculator InitGScalculator(const std::string file_name) { +GroundStationCalculator InitGScalculator(const std::string file_name) { IniAccess gs_conf(file_name); char Section[30] = "GROUND_STATION_CALCULATOR"; @@ -25,7 +25,7 @@ GScalculator InitGScalculator(const std::string file_name) { double margin_requirement_dB = gs_conf.ReadDouble(Section, "margin_requirement_dBuirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); - GScalculator gs_calculator(loss_polarization_dB, loss_atmosphere_dB, loss_rainfall_dB, loss_others_dB, ebn0_dB, hardware_deterioration_dB, - coding_gain_dB, margin_requirement_dB, downlink_bitrate_bps); + GroundStationCalculator gs_calculator(loss_polarization_dB, loss_atmosphere_dB, loss_rainfall_dB, loss_others_dB, ebn0_dB, + hardware_deterioration_dB, coding_gain_dB, margin_requirement_dB, downlink_bitrate_bps); return gs_calculator; } diff --git a/src/components/real/communication/initialize_ground_station_calculator.hpp b/src/components/real/communication/initialize_ground_station_calculator.hpp index 2861fe88c..eb3e57536 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.hpp +++ b/src/components/real/communication/initialize_ground_station_calculator.hpp @@ -14,6 +14,6 @@ * @param [in] file_name: Path to initialize file */ -GScalculator InitGScalculator(const std::string file_name); +GroundStationCalculator InitGScalculator(const std::string file_name); #endif // S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index e4b16cf96..3022ebac6 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -14,7 +14,7 @@ SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_ antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); config_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); - gs_calculator_ = new GScalculator(InitGScalculator(gscalculator_ini_path)); + gs_calculator_ = new GroundStationCalculator(InitGScalculator(gscalculator_ini_path)); } SampleGSComponents::~SampleGSComponents() { diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 14c97fe12..7d4f235dc 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -41,12 +41,12 @@ class SampleGSComponents { * @fn GetGsCalculator * @brief Return ground station calculator */ - inline GScalculator* GetGsCalculator() const { return gs_calculator_; } + inline GroundStationCalculator* GetGsCalculator() const { return gs_calculator_; } private: - Antenna* antenna_; //!< Antenna on ground station - GScalculator* gs_calculator_; //!< Ground station calculation algorithm - const SimulationConfig* config_; //!< Simulation setting + Antenna* antenna_; //!< Antenna on ground station + GroundStationCalculator* gs_calculator_; //!< Ground station calculation algorithm + const SimulationConfig* config_; //!< Simulation setting }; #endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ From f4b94de945095339d070a66bf439d1520f9b13bb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:36:02 +0100 Subject: [PATCH 0846/1086] Fix typos --- .../ground_station_calculator.cpp | 22 +++++++++---------- .../ground_station_calculator.hpp | 18 +++++++-------- .../initialize_ground_station_calculator.cpp | 12 +++++----- 3 files changed, 26 insertions(+), 26 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index bff0eab93..834a08ec1 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -11,14 +11,14 @@ GroundStationCalculator::GroundStationCalculator(const double loss_polarization_dB, const double loss_atmosphere_dB, const double loss_rainfall_dB, const double loss_others_dB, const double ebn0_dB, const double hardware_deterioration_dB, const double coding_gain_dB, const double margin_requirement_dB, const double downlink_bitrate_bps) - : loss_polarization_dB_dB_(loss_polarization_dB), - loss_atmosphere_dB_dB_(loss_atmosphere_dB), - loss_rainfall_dB_dB_(loss_rainfall_dB), - loss_others_dB_dB_(loss_others_dB), + : loss_polarization_dB_(loss_polarization_dB), + loss_atmosphere_dB_(loss_atmosphere_dB), + loss_rainfall_dB_(loss_rainfall_dB), + loss_others_dB_(loss_others_dB), ebn0_dB_(ebn0_dB), - hardware_deterioration_dB_dB_(hardware_deterioration_dB), - coding_gain_dB_dB_(coding_gain_dB), - margin_requirement_dBuirement_dB_(margin_requirement_dB), + hardware_deterioration_dB_(hardware_deterioration_dB), + coding_gain_dB_(coding_gain_dB), + margin_requirement_dB_(margin_requirement_dB), downlink_bitrate_bps_(downlink_bitrate_bps) { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -43,7 +43,7 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A const Antenna& ground_station_rx_antenna) { double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); - double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_) - margin_requirement_dBuirement_dB_; + double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_) - margin_requirement_dB_; if (margin_for_bitrate_dB > 0) { return pow(10.0, margin_for_bitrate_dB / 10.0) / 1000000.0; @@ -55,7 +55,7 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); - double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_dB_ + coding_gain_dB_dB_ + 10.0 * log10(downlink_bitrate_bps_); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(downlink_bitrate_bps_); return cn0_dB - cn0_requirement_dB; } @@ -89,8 +89,8 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = spacecraft_tx_antenna.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_dB_ + - loss_atmosphere_dB_dB_ + loss_rainfall_dB_dB_ + loss_others_dB_dB_ + + double cn0_dBHz = spacecraft_tx_antenna.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + ground_station_rx_antenna.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index 30c11db0b..edc76a56e 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -85,16 +85,16 @@ class GroundStationCalculator : public ILoggable { protected: // Parameters - double loss_polarization_dB_dB_; //!< Loss polarization [dB] - double loss_atmosphere_dB_dB_; //!< Loss atmosphere [dB] - double loss_rainfall_dB_dB_; //!< Loss rainfall [dB] - double loss_others_dB_dB_; //!< Loss others [dB] - double ebn0_dB_; //!< EbN0 [dB] - double hardware_deterioration_dB_dB_; //!< Hardware deterioration [dB] - double coding_gain_dB_dB_; //!< Coding gain [dB] + double loss_polarization_dB_; //!< Loss polarization [dB] + double loss_atmosphere_dB_; //!< Loss atmosphere [dB] + double loss_rainfall_dB_; //!< Loss rainfall [dB] + double loss_others_dB_; //!< Loss others [dB] + double ebn0_dB_; //!< EbN0 [dB] + double hardware_deterioration_dB_; //!< Hardware deterioration [dB] + double coding_gain_dB_; //!< Coding gain [dB] // Variables - double margin_requirement_dBuirement_dB_; //!< Required margin to calculate max bitrate [dB] - double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] + double margin_requirement_dB_; //!< Required margin to calculate max bitrate [dB] + double downlink_bitrate_bps_; //!< Downlink bitrate to calculate receive margin [bps] // Calculated values double receive_margin_dB_; //!< Receive margin [dB] diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index 0d4056b60..9497e06ea 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -15,13 +15,13 @@ GroundStationCalculator InitGScalculator(const std::string file_name) { char Section[30] = "GROUND_STATION_CALCULATOR"; - double loss_polarization_dB = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB_dB"); - double loss_atmosphere_dB = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB_dB"); - double loss_rainfall_dB = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB_dB"); - double loss_others_dB = gs_conf.ReadDouble(Section, "loss_others_dB_dB_dB"); + double loss_polarization_dB = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB"); + double loss_atmosphere_dB = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB"); + double loss_rainfall_dB = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB"); + double loss_others_dB = gs_conf.ReadDouble(Section, "loss_others_dB_dB"); double ebn0_dB = gs_conf.ReadDouble(Section, "ebn0_dB"); - double hardware_deterioration_dB = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB_dB"); - double coding_gain_dB = gs_conf.ReadDouble(Section, "coding_gain_dB_dB_dB"); + double hardware_deterioration_dB = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB"); + double coding_gain_dB = gs_conf.ReadDouble(Section, "coding_gain_dB_dB"); double margin_requirement_dB = gs_conf.ReadDouble(Section, "margin_requirement_dBuirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); From f151c536ab37474703a15d58ee37cf509579a639 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:36:44 +0100 Subject: [PATCH 0847/1086] Fix initialize function name --- .../real/communication/initialize_ground_station_calculator.cpp | 2 +- .../real/communication/initialize_ground_station_calculator.hpp | 2 +- .../sample_ground_station/sample_ground_station_components.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index 9497e06ea..5573e84b1 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -GroundStationCalculator InitGScalculator(const std::string file_name) { +GroundStationCalculator InitGsCalculator(const std::string file_name) { IniAccess gs_conf(file_name); char Section[30] = "GROUND_STATION_CALCULATOR"; diff --git a/src/components/real/communication/initialize_ground_station_calculator.hpp b/src/components/real/communication/initialize_ground_station_calculator.hpp index eb3e57536..298b459c6 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.hpp +++ b/src/components/real/communication/initialize_ground_station_calculator.hpp @@ -14,6 +14,6 @@ * @param [in] file_name: Path to initialize file */ -GroundStationCalculator InitGScalculator(const std::string file_name); +GroundStationCalculator InitGsCalculator(const std::string file_name); #endif // S2E_COMPONENTS_REAL_COMMUNICATION_INITIALIZE_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 3022ebac6..dc9898c1a 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -14,7 +14,7 @@ SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_ antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); config_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); - gs_calculator_ = new GroundStationCalculator(InitGScalculator(gscalculator_ini_path)); + gs_calculator_ = new GroundStationCalculator(InitGsCalculator(gscalculator_ini_path)); } SampleGSComponents::~SampleGSComponents() { From 4e8079126d6092d5c5f472261c5692880e4031e1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:39:47 +0100 Subject: [PATCH 0848/1086] Fix private variables name --- src/components/real/power/battery.cpp | 68 +++++++++---------- src/components/real/power/battery.hpp | 22 +++--- .../real/power/initialize_battery.cpp | 2 +- .../real/power/pcu_initial_study.cpp | 32 ++++----- .../real/power/pcu_initial_study.hpp | 14 ++-- .../real/power/solar_array_panel.cpp | 10 +-- .../real/power/solar_array_panel.hpp | 2 +- 7 files changed, 75 insertions(+), 75 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index ec0404b2b..bcb59e179 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -13,13 +13,13 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_ser : Component(prescaler, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_capacity_(cell_capacity), - cell_discharge_curve_coeffs_(cell_discharge_curve_coeffs), - cc_charge_current_(cc_charge_c_rate * cell_capacity * number_of_parallel), - cv_charge_voltage_(cv_charge_voltage), - dod_(initial_dod), - bat_resistance_(bat_resistance), - compo_step_time_(component_step_time_s) {} + cell_capacity_Ah_(cell_capacity), + cell_discharge_curve_coefficients_(cell_discharge_curve_coeffs), + cc_charge_current_A_C_(cc_charge_c_rate * cell_capacity * number_of_parallel), + cv_charge_voltage_V_(cv_charge_voltage), + depth_of_discharge_percent_(initial_dod), + bat_resistance_Ohm_(bat_resistance), + compo_step_time_s_(component_step_time_s) {} BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, @@ -27,40 +27,40 @@ BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_pa : Component(10, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_capacity_(cell_capacity), - cell_discharge_curve_coeffs_(cell_discharge_curve_coeffs), - cc_charge_current_(cc_charge_c_rate * cell_capacity * number_of_parallel), - cv_charge_voltage_(cv_charge_voltage), - dod_(initial_dod), - bat_resistance_(bat_resistance), - compo_step_time_(0.1) {} + cell_capacity_Ah_(cell_capacity), + cell_discharge_curve_coefficients_(cell_discharge_curve_coeffs), + cc_charge_current_A_C_(cc_charge_c_rate * cell_capacity * number_of_parallel), + cv_charge_voltage_V_(cv_charge_voltage), + depth_of_discharge_percent_(initial_dod), + bat_resistance_Ohm_(bat_resistance), + compo_step_time_s_(0.1) {} BAT::BAT(const BAT& obj) : Component(obj), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), - cell_capacity_(obj.cell_capacity_), - cell_discharge_curve_coeffs_(obj.cell_discharge_curve_coeffs_), - cc_charge_current_(obj.cc_charge_current_), - cv_charge_voltage_(obj.cv_charge_voltage_), - dod_(obj.dod_), - bat_resistance_(obj.bat_resistance_), - compo_step_time_(obj.compo_step_time_) { - charge_current_ = 0.0; + cell_capacity_Ah_(obj.cell_capacity_Ah_), + cell_discharge_curve_coefficients_(obj.cell_discharge_curve_coefficients_), + cc_charge_current_A_C_(obj.cc_charge_current_A_C_), + cv_charge_voltage_V_(obj.cv_charge_voltage_V_), + depth_of_discharge_percent_(obj.depth_of_discharge_percent_), + bat_resistance_Ohm_(obj.bat_resistance_Ohm_), + compo_step_time_s_(obj.compo_step_time_s_) { + charge_current_A_ = 0.0; UpdateBatVoltage(); } BAT::~BAT() {} -void BAT::SetChargeCurrent(const double current) { charge_current_ = current; } +void BAT::SetChargeCurrent(const double current) { charge_current_A_ = current; } -double BAT::GetBatVoltage() const { return bat_voltage_; } +double BAT::GetBatVoltage() const { return battery_voltage_V_; } -double BAT::GetBatResistance() const { return bat_resistance_; } +double BAT::GetBatResistance() const { return bat_resistance_Ohm_; } -double BAT::GetCCChargeCurrent() const { return cc_charge_current_; } +double BAT::GetCCChargeCurrent() const { return cc_charge_current_A_C_; } -double BAT::GetCVChargeVoltage() const { return cv_charge_voltage_; } +double BAT::GetCVChargeVoltage() const { return cv_charge_voltage_V_; } std::string BAT::GetLogHeader() const { std::string str_tmp = ""; @@ -72,26 +72,26 @@ std::string BAT::GetLogHeader() const { std::string BAT::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(bat_voltage_); - str_tmp += WriteScalar(dod_); + str_tmp += WriteScalar(battery_voltage_V_); + str_tmp += WriteScalar(depth_of_discharge_percent_); return str_tmp; } void BAT::MainRoutine(int time_count) { UNUSED(time_count); - double delta_time_query = compo_step_time_ * prescaler_; - dod_ -= charge_current_ * delta_time_query / 3600.0 / (cell_capacity_ * number_of_parallel_) * 100.0; + double delta_time_query = compo_step_time_s_ * prescaler_; + depth_of_discharge_percent_ -= charge_current_A_ * delta_time_query / 3600.0 / (cell_capacity_Ah_ * number_of_parallel_) * 100.0; UpdateBatVoltage(); } void BAT::UpdateBatVoltage() { - double cell_discharge_capasity = dod_ / 100.0 * cell_capacity_; + double cell_discharge_capasity = depth_of_discharge_percent_ / 100.0 * cell_capacity_Ah_; double temp = 0.0; int index = 0; - for (auto coeff : cell_discharge_curve_coeffs_) { + for (auto coeff : cell_discharge_curve_coefficients_) { temp += coeff * std::pow(cell_discharge_capasity, index); ++index; } - bat_voltage_ = temp * number_of_series_; + battery_voltage_V_ = temp * number_of_series_; } diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index a988db08d..7ff317b99 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -106,17 +106,17 @@ class BAT : public Component, public ILoggable { std::string GetLogValue() const override; private: - const int number_of_series_; //!< Number of series connected cells - const int number_of_parallel_; //!< Number of parallel connected cells - const double cell_capacity_; //!< Power capacity of a cell [Ah] - const std::vector cell_discharge_curve_coeffs_; //!< Discharge curve coefficients for a cell - const double cc_charge_current_; //!< Constant charge current [C] - const double cv_charge_voltage_; //!< Constant charge voltage [V] - double bat_voltage_; //!< Battery voltage [V] - double dod_; //!< Depth of discharge [%] - double charge_current_; //!< Charge current [A] - double bat_resistance_; //!< Battery internal resistance [Ohm] - double compo_step_time_; //!< Component step time [sec] + const int number_of_series_; //!< Number of series connected cells + const int number_of_parallel_; //!< Number of parallel connected cells + const double cell_capacity_Ah_; //!< Power capacity of a cell [Ah] + const std::vector cell_discharge_curve_coefficients_; //!< Discharge curve coefficients for a cell + const double cc_charge_current_A_C_; //!< Constant charge current [C] + const double cv_charge_voltage_V_; //!< Constant charge voltage [V] + double battery_voltage_V_; //!< Battery voltage [V] + double depth_of_discharge_percent_; //!< Depth of discharge [%] + double charge_current_A_; //!< Charge current [A] + double bat_resistance_Ohm_; //!< Battery internal resistance [Ohm] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index c4053becc..3d9b29556 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -43,7 +43,7 @@ BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_ initial_dod = bat_conf.ReadDouble(Section, "initial_dod"); double cc_charge_c_rate; - cc_charge_c_rate = bat_conf.ReadDouble(Section, "constant_charge_current_rate_C"); + cc_charge_c_rate = bat_conf.ReadDouble(Section, "constant_charge_current_A_rate_C"); double cv_charge_voltage; cv_charge_voltage = bat_conf.ReadDouble(Section, "constant_voltage_charge_voltage_V"); diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index ebfbe7010..7b4507c5e 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -14,9 +14,9 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge : Component(prescaler, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_(bat->GetCCChargeCurrent()), - cv_charge_voltage_(bat->GetCVChargeVoltage()), - compo_step_time_(component_step_time_s) { + cc_charge_current_A_C_(bat->GetCCChargeCurrent()), + cv_charge_voltage_V_(bat->GetCVChargeVoltage()), + compo_step_time_s_(component_step_time_s) { bus_voltage_ = 0.0; power_consumption_ = 0.0; } @@ -25,9 +25,9 @@ PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::v : Component(10, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_(bat->GetCCChargeCurrent()), - cv_charge_voltage_(bat->GetCVChargeVoltage()), - compo_step_time_(0.1) { + cc_charge_current_A_C_(bat->GetCCChargeCurrent()), + cv_charge_voltage_V_(bat->GetCVChargeVoltage()), + compo_step_time_s_(0.1) { bus_voltage_ = 0.0; power_consumption_ = 0.0; } @@ -50,7 +50,7 @@ std::string PCU_InitialStudy::GetLogValue() const { } void PCU_InitialStudy::MainRoutine(int time_count) { - double time_query = compo_step_time_ * time_count; + double time_query = compo_step_time_s_ * time_count; power_consumption_ = CalcPowerConsumption(time_query); // Should use SimulationTime? time_count may over flow since it is int type, UpdateChargeCurrentAndBusVoltage(); @@ -86,25 +86,25 @@ void PCU_InitialStudy::UpdateChargeCurrentAndBusVoltage() { } double current_temp = (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * bat_resistance * (power_generation - power_consumption_))) / (2.0 * bat_resistance); - if (current_temp >= cc_charge_current_) { - if (bat_voltage + cc_charge_current_ * bat_resistance < cv_charge_voltage_) { + if (current_temp >= cc_charge_current_A_C_) { + if (bat_voltage + cc_charge_current_A_C_ * bat_resistance < cv_charge_voltage_V_) { // CC Charge - bat_->SetChargeCurrent(cc_charge_current_); - bus_voltage_ = bat_voltage + bat_resistance * cc_charge_current_; + bat_->SetChargeCurrent(cc_charge_current_A_C_); + bus_voltage_ = bat_voltage + bat_resistance * cc_charge_current_A_C_; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_ - bat_voltage) / bat_resistance); - bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_ - bat_voltage) / bat_resistance; + bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / bat_resistance); + bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_V_ - bat_voltage) / bat_resistance; } } else { - if (bat_voltage + current_temp * bat_resistance < cv_charge_voltage_) { + if (bat_voltage + current_temp * bat_resistance < cv_charge_voltage_V_) { // Natural charge or discharge bat_->SetChargeCurrent(current_temp); bus_voltage_ = bat_voltage + bat_resistance * current_temp; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_ - bat_voltage) / bat_resistance); - bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_ - bat_voltage) / bat_resistance; + bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / bat_resistance); + bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_V_ - bat_voltage) / bat_resistance; } } } diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index a75737b4d..cf32efd0d 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -52,13 +52,13 @@ class PCU_InitialStudy : public Component, public ILoggable { std::string GetLogValue() const override; private: - const std::vector saps_; //!< Solar Array Panels - BAT* const bat_; //!< Battery - const double cc_charge_current_; //!< Constant charge current [C] - const double cv_charge_voltage_; //!< Constant charge voltage [V] - double bus_voltage_; //!< Bus voltage [V] - double power_consumption_; //!< Power consumption [W] - double compo_step_time_; //!< Component step time [sec] + const std::vector saps_; //!< Solar Array Panels + BAT* const bat_; //!< Battery + const double cc_charge_current_A_C_; //!< Constant charge current [C] + const double cv_charge_voltage_V_; //!< Constant charge voltage [V] + double bus_voltage_; //!< Bus voltage [V] + double power_consumption_; //!< Power consumption [W] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index ea9b5f522..b79cd5d15 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -21,7 +21,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, transmission_efficiency_(transmission_efficiency), srp_(srp), local_celestial_information_(local_celestial_information), - compo_step_time_(component_step_time_s) { + compo_step_time_s_(component_step_time_s) { voltage_ = 0.0; power_generation_ = 0.0; } @@ -38,7 +38,7 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_(srp), - compo_step_time_(component_step_time_s) { + compo_step_time_s_(component_step_time_s) { voltage_ = 0.0; power_generation_ = 0.0; } @@ -56,7 +56,7 @@ SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series transmission_efficiency_(transmission_efficiency), srp_(srp), local_celestial_information_(local_celestial_information), - compo_step_time_(0.1) { + compo_step_time_s_(0.1) { voltage_ = 0.0; power_generation_ = 0.0; } @@ -72,7 +72,7 @@ SAP::SAP(const SAP& obj) transmission_efficiency_(obj.transmission_efficiency_), srp_(obj.srp_), local_celestial_information_(obj.local_celestial_information_), - compo_step_time_(obj.compo_step_time_) { + compo_step_time_s_(obj.compo_step_time_s_) { voltage_ = 0.0; power_generation_ = 0.0; } @@ -98,7 +98,7 @@ std::string SAP::GetLogValue() const { void SAP::MainRoutine(int time_count) { if (CsvScenarioInterface::IsCsvScenarioEnabled()) { - double time_query = compo_step_time_ * time_count; + double time_query = compo_step_time_s_ * time_count; const auto solar_constant = srp_->GetSolarConstant_W_m2(); libra::Vector<3> sun_direction_body = CsvScenarioInterface::GetSunDirectionBody(time_query); libra::Vector<3> normalized_sun_direction_body = libra::Normalize(sun_direction_body); diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index dca9f83b8..38282044a 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -121,7 +121,7 @@ class SAP : public Component, public ILoggable { static const double solar_constant_; //!< Solar constant TODO: Use SolarRadiationPressureEnvironment? static const double light_speed_; //!< Speed of light TODO: Use PhysicalConstant? - double compo_step_time_; //!< Component step time [sec] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** From 9d70422c4af591cb06b76f0b50b715e9917a4d44 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:46:16 +0100 Subject: [PATCH 0849/1086] Fix function argument name --- src/components/real/power/battery.cpp | 36 +++++++++---------- src/components/real/power/battery.hpp | 33 +++++++++-------- .../real/power/initialize_battery.cpp | 21 +++++------ .../real/power/pcu_initial_study.cpp | 29 +++++++-------- .../real/power/pcu_initial_study.hpp | 14 ++++---- 5 files changed, 67 insertions(+), 66 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index bcb59e179..2b8df99e1 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -7,32 +7,32 @@ #include -BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, - const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance, double component_step_time_s) +BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm, double component_step_time_s) : Component(prescaler, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_capacity_Ah_(cell_capacity), - cell_discharge_curve_coefficients_(cell_discharge_curve_coeffs), - cc_charge_current_A_C_(cc_charge_c_rate * cell_capacity * number_of_parallel), - cv_charge_voltage_V_(cv_charge_voltage), + cell_capacity_Ah_(cell_capacity_Ah), + cell_discharge_curve_coefficients_(cell_discharge_curve_coefficients), + cc_charge_current_C_(cc_charge_c_rate * cell_capacity_Ah * number_of_parallel), + cv_charge_voltage_V_(cv_charge_voltage_V), depth_of_discharge_percent_(initial_dod), - bat_resistance_Ohm_(bat_resistance), + bat_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(component_step_time_s) {} -BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, - const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance) +BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm) : Component(10, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_capacity_Ah_(cell_capacity), - cell_discharge_curve_coefficients_(cell_discharge_curve_coeffs), - cc_charge_current_A_C_(cc_charge_c_rate * cell_capacity * number_of_parallel), - cv_charge_voltage_V_(cv_charge_voltage), + cell_capacity_Ah_(cell_capacity_Ah), + cell_discharge_curve_coefficients_(cell_discharge_curve_coefficients), + cc_charge_current_C_(cc_charge_c_rate * cell_capacity_Ah * number_of_parallel), + cv_charge_voltage_V_(cv_charge_voltage_V), depth_of_discharge_percent_(initial_dod), - bat_resistance_Ohm_(bat_resistance), + bat_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(0.1) {} BAT::BAT(const BAT& obj) @@ -41,7 +41,7 @@ BAT::BAT(const BAT& obj) number_of_parallel_(obj.number_of_parallel_), cell_capacity_Ah_(obj.cell_capacity_Ah_), cell_discharge_curve_coefficients_(obj.cell_discharge_curve_coefficients_), - cc_charge_current_A_C_(obj.cc_charge_current_A_C_), + cc_charge_current_C_(obj.cc_charge_current_C_), cv_charge_voltage_V_(obj.cv_charge_voltage_V_), depth_of_discharge_percent_(obj.depth_of_discharge_percent_), bat_resistance_Ohm_(obj.bat_resistance_Ohm_), @@ -58,7 +58,7 @@ double BAT::GetBatVoltage() const { return battery_voltage_V_; } double BAT::GetBatResistance() const { return bat_resistance_Ohm_; } -double BAT::GetCCChargeCurrent() const { return cc_charge_current_A_C_; } +double BAT::GetCCChargeCurrent() const { return cc_charge_current_C_; } double BAT::GetCVChargeVoltage() const { return cv_charge_voltage_V_; } diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 7ff317b99..13df4bade 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -24,17 +24,17 @@ class BAT : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] number_of_series: Number of series connected cells * @param [in] number_of_parallel: Number of parallel connected cells - * @param [in] cell_capacity: Power capacity of a cell [Ah] - * @param [in] cell_discharge_curve_coeffs: Discharge curve coefficients for a cell + * @param [in] cell_capacity_Ah: Power capacity of a cell [Ah] + * @param [in] cell_discharge_curve_coefficients: Discharge curve coefficients for a cell * @param [in] initial_dod: Initial depth of discharge - * @param [in] cc_charge_c_rate: Constant charge current [C] - * @param [in] cv_charge_voltage: Constant charge voltage [V] - * @param [in] bat_resistance: Battery internal resistance [Ohm] + * @param [in] cc_charge_c_rate: Constant charge rate [C] + * @param [in] cv_charge_voltage_V: Constant charge voltage [V] + * @param [in] battery_resistance_Ohm: Battery internal resistance [Ohm] * @param [in] component_step_time_s: Component step time [sec] */ - BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, - const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance, double component_step_time_s); + BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm, double component_step_time_s); /** * @fn BAT * @brief Constructor without prescaler @@ -42,17 +42,16 @@ class BAT : public Component, public ILoggable { * @param [in] clock_generator: Clock generator * @param [in] number_of_series: Number of series connected cells * @param [in] number_of_parallel: Number of parallel connected cells - * @param [in] cell_capacity: Power capacity of a cell [Ah] - * @param [in] cell_discharge_curve_coeffs: Discharge curve coefficients for a cell + * @param [in] cell_capacity_Ah: Power capacity of a cell [Ah] + * @param [in] cell_discharge_curve_coefficients: Discharge curve coefficients for a cell * @param [in] initial_dod: Initial depth of discharge * @param [in] cc_charge_c_rate: Constant charge current [C] - * @param [in] cv_charge_voltage: Constant charge voltage [V] - * @param [in] bat_resistance: Battery internal resistance [Ohm] - * @param [in] component_step_time_s: Component step time [sec] + * @param [in] cv_charge_voltage_V: Constant charge voltage [V] + * @param [in] battery_resistance_Ohm: Battery internal resistance [Ohm] */ - BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity, - const std::vector cell_discharge_curve_coeffs, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage, - double bat_resistance); + BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm); /** * @fn BAT * @brief Copy constructor @@ -110,7 +109,7 @@ class BAT : public Component, public ILoggable { const int number_of_parallel_; //!< Number of parallel connected cells const double cell_capacity_Ah_; //!< Power capacity of a cell [Ah] const std::vector cell_discharge_curve_coefficients_; //!< Discharge curve coefficients for a cell - const double cc_charge_current_A_C_; //!< Constant charge current [C] + const double cc_charge_current_C_; //!< Constant charge current [C] const double cv_charge_voltage_V_; //!< Constant charge voltage [V] double battery_voltage_V_; //!< Battery voltage [V] double depth_of_discharge_percent_; //!< Depth of discharge [%] diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index 3d9b29556..71b08501f 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -28,15 +28,16 @@ BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_ int number_of_parallel; number_of_parallel = bat_conf.ReadInt(Section, "number_of_parallel"); - double cell_capacity; - cell_capacity = bat_conf.ReadDouble(Section, "cell_capacity"); + double cell_capacity_Ah; + cell_capacity_Ah = bat_conf.ReadDouble(Section, "cell_capacity_Ah"); int approx_order; approx_order = bat_conf.ReadInt(Section, "approximation_order"); - std::vector cell_discharge_curve_coeffs; + std::vector cell_discharge_curve_coefficients; for (int i = 0; i <= approx_order; ++i) { - cell_discharge_curve_coeffs.push_back(bat_conf.ReadDouble(Section, ("cell_discharge_curve_coefficients(" + std::to_string(i) + ")").c_str())); + cell_discharge_curve_coefficients.push_back( + bat_conf.ReadDouble(Section, ("cell_discharge_curve_coefficients(" + std::to_string(i) + ")").c_str())); } double initial_dod; @@ -45,14 +46,14 @@ BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_ double cc_charge_c_rate; cc_charge_c_rate = bat_conf.ReadDouble(Section, "constant_charge_current_A_rate_C"); - double cv_charge_voltage; - cv_charge_voltage = bat_conf.ReadDouble(Section, "constant_voltage_charge_voltage_V"); + double cv_charge_voltage_V; + cv_charge_voltage_V = bat_conf.ReadDouble(Section, "constant_voltage_charge_voltage_V"); - double bat_resistance; - bat_resistance = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); + double battery_resistance_Ohm; + battery_resistance_Ohm = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); - BAT bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity, cell_discharge_curve_coeffs, initial_dod, cc_charge_c_rate, - cv_charge_voltage, bat_resistance, component_step_time_s); + BAT bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity_Ah, cell_discharge_curve_coefficients, initial_dod, + cc_charge_c_rate, cv_charge_voltage_V, battery_resistance_Ohm, component_step_time_s); return bat; } diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 7b4507c5e..10c0f2603 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -14,7 +14,7 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge : Component(prescaler, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_A_C_(bat->GetCCChargeCurrent()), + cc_charge_current_C_(bat->GetCCChargeCurrent()), cv_charge_voltage_V_(bat->GetCVChargeVoltage()), compo_step_time_s_(component_step_time_s) { bus_voltage_ = 0.0; @@ -25,7 +25,7 @@ PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::v : Component(10, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_A_C_(bat->GetCCChargeCurrent()), + cc_charge_current_C_(bat->GetCCChargeCurrent()), cv_charge_voltage_V_(bat->GetCVChargeVoltage()), compo_step_time_s_(0.1) { bus_voltage_ = 0.0; @@ -79,32 +79,33 @@ double PCU_InitialStudy::CalcPowerConsumption(double time_query) const { void PCU_InitialStudy::UpdateChargeCurrentAndBusVoltage() { double bat_voltage = bat_->GetBatVoltage(); - const double bat_resistance = bat_->GetBatResistance(); + const double battery_resistance_Ohm = bat_->GetBatResistance(); double power_generation = 0.0; for (auto sap : saps_) { power_generation += sap->GetPowerGeneration(); } double current_temp = - (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * bat_resistance * (power_generation - power_consumption_))) / (2.0 * bat_resistance); - if (current_temp >= cc_charge_current_A_C_) { - if (bat_voltage + cc_charge_current_A_C_ * bat_resistance < cv_charge_voltage_V_) { + (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * battery_resistance_Ohm * (power_generation - power_consumption_))) / + (2.0 * battery_resistance_Ohm); + if (current_temp >= cc_charge_current_C_) { + if (bat_voltage + cc_charge_current_C_ * battery_resistance_Ohm < cv_charge_voltage_V_) { // CC Charge - bat_->SetChargeCurrent(cc_charge_current_A_C_); - bus_voltage_ = bat_voltage + bat_resistance * cc_charge_current_A_C_; + bat_->SetChargeCurrent(cc_charge_current_C_); + bus_voltage_ = bat_voltage + battery_resistance_Ohm * cc_charge_current_C_; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / bat_resistance); - bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_V_ - bat_voltage) / bat_resistance; + bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); + bus_voltage_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; } } else { - if (bat_voltage + current_temp * bat_resistance < cv_charge_voltage_V_) { + if (bat_voltage + current_temp * battery_resistance_Ohm < cv_charge_voltage_V_) { // Natural charge or discharge bat_->SetChargeCurrent(current_temp); - bus_voltage_ = bat_voltage + bat_resistance * current_temp; + bus_voltage_ = bat_voltage + battery_resistance_Ohm * current_temp; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / bat_resistance); - bus_voltage_ = bat_voltage + bat_resistance * (cv_charge_voltage_V_ - bat_voltage) / bat_resistance; + bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); + bus_voltage_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; } } } diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index cf32efd0d..7c194751d 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -52,13 +52,13 @@ class PCU_InitialStudy : public Component, public ILoggable { std::string GetLogValue() const override; private: - const std::vector saps_; //!< Solar Array Panels - BAT* const bat_; //!< Battery - const double cc_charge_current_A_C_; //!< Constant charge current [C] - const double cv_charge_voltage_V_; //!< Constant charge voltage [V] - double bus_voltage_; //!< Bus voltage [V] - double power_consumption_; //!< Power consumption [W] - double compo_step_time_s_; //!< Component step time [sec] + const std::vector saps_; //!< Solar Array Panels + BAT* const bat_; //!< Battery + const double cc_charge_current_C_; //!< Constant charge current [C] + const double cv_charge_voltage_V_; //!< Constant charge voltage [V] + double bus_voltage_; //!< Bus voltage [V] + double power_consumption_; //!< Power consumption [W] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** From 0a2165e2388debd4389d44291b6d9544893a4bfe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:51:55 +0100 Subject: [PATCH 0850/1086] Move to inline functions --- src/components/real/power/battery.cpp | 10 ---------- src/components/real/power/battery.hpp | 13 ++++++++----- 2 files changed, 8 insertions(+), 15 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 2b8df99e1..d0f0f4f34 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -52,16 +52,6 @@ BAT::BAT(const BAT& obj) BAT::~BAT() {} -void BAT::SetChargeCurrent(const double current) { charge_current_A_ = current; } - -double BAT::GetBatVoltage() const { return battery_voltage_V_; } - -double BAT::GetBatResistance() const { return bat_resistance_Ohm_; } - -double BAT::GetCCChargeCurrent() const { return cc_charge_current_C_; } - -double BAT::GetCVChargeVoltage() const { return cv_charge_voltage_V_; } - std::string BAT::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "battery_"; diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 13df4bade..2f582a282 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -67,30 +67,33 @@ class BAT : public Component, public ILoggable { * @fn SetChargeCurrent * @brief Set charge current [A] */ - void SetChargeCurrent(const double current); + inline void SetChargeCurrent(const double current) { charge_current_A_ = current; } /** * @fn GetBatVoltage * @brief Return battery voltage [V] */ - double GetBatVoltage() const; + inline double GetBatVoltage() const { return battery_voltage_V_; } + /** * @fn GetBatResistance * @brief Return battery resistance [Ohm] */ - double GetBatResistance() const; + inline double GetBatResistance() const { return bat_resistance_Ohm_; } + /** * @fn GetCCChargeCurrent * @brief Return constant charge current [C] * @note TODO: Change implementation? */ - double GetCCChargeCurrent() const; + inline double GetCCChargeCurrent() const { return cc_charge_current_C_; } + /** * @fn GetCVChargeVoltage * @brief Return constant charge voltage [V] * @note TODO: Change implementation? */ - double GetCVChargeVoltage() const; + inline double GetCVChargeVoltage() const { return cv_charge_voltage_V_; } // Override ILoggable /** From 1bcdb25337b3dce69d3f3ffe552e8f516542ae99 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:54:00 +0100 Subject: [PATCH 0851/1086] Fix public function name --- src/components/real/power/battery.cpp | 6 +++--- src/components/real/power/battery.hpp | 20 +++++++++---------- .../real/power/pcu_initial_study.cpp | 12 +++++------ 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index d0f0f4f34..8261c9e94 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -18,7 +18,7 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_ser cc_charge_current_C_(cc_charge_c_rate * cell_capacity_Ah * number_of_parallel), cv_charge_voltage_V_(cv_charge_voltage_V), depth_of_discharge_percent_(initial_dod), - bat_resistance_Ohm_(battery_resistance_Ohm), + battery_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(component_step_time_s) {} BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, @@ -32,7 +32,7 @@ BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_pa cc_charge_current_C_(cc_charge_c_rate * cell_capacity_Ah * number_of_parallel), cv_charge_voltage_V_(cv_charge_voltage_V), depth_of_discharge_percent_(initial_dod), - bat_resistance_Ohm_(battery_resistance_Ohm), + battery_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(0.1) {} BAT::BAT(const BAT& obj) @@ -44,7 +44,7 @@ BAT::BAT(const BAT& obj) cc_charge_current_C_(obj.cc_charge_current_C_), cv_charge_voltage_V_(obj.cv_charge_voltage_V_), depth_of_discharge_percent_(obj.depth_of_discharge_percent_), - bat_resistance_Ohm_(obj.bat_resistance_Ohm_), + battery_resistance_Ohm_(obj.battery_resistance_Ohm_), compo_step_time_s_(obj.compo_step_time_s_) { charge_current_A_ = 0.0; UpdateBatVoltage(); diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 2f582a282..9b0b4394a 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -67,33 +67,33 @@ class BAT : public Component, public ILoggable { * @fn SetChargeCurrent * @brief Set charge current [A] */ - inline void SetChargeCurrent(const double current) { charge_current_A_ = current; } + inline void SetChargeCurrent(const double current_A) { charge_current_A_ = current_A; } /** - * @fn GetBatVoltage + * @fn GetVoltage_V * @brief Return battery voltage [V] */ - inline double GetBatVoltage() const { return battery_voltage_V_; } + inline double GetVoltage_V() const { return battery_voltage_V_; } /** - * @fn GetBatResistance + * @fn GetResistance_Ohm * @brief Return battery resistance [Ohm] */ - inline double GetBatResistance() const { return bat_resistance_Ohm_; } + inline double GetResistance_Ohm() const { return battery_resistance_Ohm_; } /** - * @fn GetCCChargeCurrent + * @fn GetCcChargeCurrent_C * @brief Return constant charge current [C] * @note TODO: Change implementation? */ - inline double GetCCChargeCurrent() const { return cc_charge_current_C_; } + inline double GetCcChargeCurrent_C() const { return cc_charge_current_C_; } /** - * @fn GetCVChargeVoltage + * @fn GetCvChargeVoltage_V * @brief Return constant charge voltage [V] * @note TODO: Change implementation? */ - inline double GetCVChargeVoltage() const { return cv_charge_voltage_V_; } + inline double GetCvChargeVoltage_V() const { return cv_charge_voltage_V_; } // Override ILoggable /** @@ -117,7 +117,7 @@ class BAT : public Component, public ILoggable { double battery_voltage_V_; //!< Battery voltage [V] double depth_of_discharge_percent_; //!< Depth of discharge [%] double charge_current_A_; //!< Charge current [A] - double bat_resistance_Ohm_; //!< Battery internal resistance [Ohm] + double battery_resistance_Ohm_; //!< Battery internal resistance [Ohm] double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 10c0f2603..afa3423d4 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -14,8 +14,8 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge : Component(prescaler, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_C_(bat->GetCCChargeCurrent()), - cv_charge_voltage_V_(bat->GetCVChargeVoltage()), + cc_charge_current_C_(bat->GetCcChargeCurrent_C()), + cv_charge_voltage_V_(bat->GetCvChargeVoltage_V()), compo_step_time_s_(component_step_time_s) { bus_voltage_ = 0.0; power_consumption_ = 0.0; @@ -25,8 +25,8 @@ PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::v : Component(10, clock_generator), saps_(saps), bat_(bat), - cc_charge_current_C_(bat->GetCCChargeCurrent()), - cv_charge_voltage_V_(bat->GetCVChargeVoltage()), + cc_charge_current_C_(bat->GetCcChargeCurrent_C()), + cv_charge_voltage_V_(bat->GetCvChargeVoltage_V()), compo_step_time_s_(0.1) { bus_voltage_ = 0.0; power_consumption_ = 0.0; @@ -78,8 +78,8 @@ double PCU_InitialStudy::CalcPowerConsumption(double time_query) const { } void PCU_InitialStudy::UpdateChargeCurrentAndBusVoltage() { - double bat_voltage = bat_->GetBatVoltage(); - const double battery_resistance_Ohm = bat_->GetBatResistance(); + double bat_voltage = bat_->GetVoltage_V(); + const double battery_resistance_Ohm = bat_->GetResistance_Ohm(); double power_generation = 0.0; for (auto sap : saps_) { power_generation += sap->GetPowerGeneration(); From 40b1b0664c366a0d08b2175fc3e22705c3185862 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:54:31 +0100 Subject: [PATCH 0852/1086] Fix function argument names --- src/components/real/power/battery.cpp | 2 +- src/components/real/power/battery.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 8261c9e94..4d3d9cc09 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -67,7 +67,7 @@ std::string BAT::GetLogValue() const { return str_tmp; } -void BAT::MainRoutine(int time_count) { +void BAT::MainRoutine(const int time_count) { UNUSED(time_count); double delta_time_query = compo_step_time_s_ * prescaler_; diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 9b0b4394a..5cfe8c473 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -125,7 +125,7 @@ class BAT : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; /** * @fn UpdateBatVoltage From c5be9093ed6bdb05085232c04a6cda9ecc83d448 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:55:08 +0100 Subject: [PATCH 0853/1086] Rename BAT to Battery --- src/components/real/power/battery.cpp | 24 ++++++++-------- src/components/real/power/battery.hpp | 28 +++++++++---------- .../real/power/initialize_battery.cpp | 8 +++--- .../real/power/initialize_battery.hpp | 6 ++-- .../power/initialize_pcu_initial_study.cpp | 4 +-- .../power/initialize_pcu_initial_study.hpp | 6 ++-- .../power/initialize_solar_array_panel.hpp | 4 +-- .../real/power/pcu_initial_study.cpp | 4 +-- .../real/power/pcu_initial_study.hpp | 6 ++-- 9 files changed, 45 insertions(+), 45 deletions(-) diff --git a/src/components/real/power/battery.cpp b/src/components/real/power/battery.cpp index 4d3d9cc09..07b2cdf0c 100644 --- a/src/components/real/power/battery.cpp +++ b/src/components/real/power/battery.cpp @@ -7,9 +7,9 @@ #include -BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, - const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, - double battery_resistance_Ohm, double component_step_time_s) +Battery::Battery(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm, double component_step_time_s) : Component(prescaler, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -21,9 +21,9 @@ BAT::BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_ser battery_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(component_step_time_s) {} -BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, - const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, - double battery_resistance_Ohm) +Battery::Battery(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm) : Component(10, clock_generator), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), @@ -35,7 +35,7 @@ BAT::BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_pa battery_resistance_Ohm_(battery_resistance_Ohm), compo_step_time_s_(0.1) {} -BAT::BAT(const BAT& obj) +Battery::Battery(const Battery& obj) : Component(obj), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), @@ -50,9 +50,9 @@ BAT::BAT(const BAT& obj) UpdateBatVoltage(); } -BAT::~BAT() {} +Battery::~Battery() {} -std::string BAT::GetLogHeader() const { +std::string Battery::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "battery_"; str_tmp += WriteScalar(component_name + "voltage", "V"); @@ -60,14 +60,14 @@ std::string BAT::GetLogHeader() const { return str_tmp; } -std::string BAT::GetLogValue() const { +std::string Battery::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(battery_voltage_V_); str_tmp += WriteScalar(depth_of_discharge_percent_); return str_tmp; } -void BAT::MainRoutine(const int time_count) { +void Battery::MainRoutine(const int time_count) { UNUSED(time_count); double delta_time_query = compo_step_time_s_ * prescaler_; @@ -75,7 +75,7 @@ void BAT::MainRoutine(const int time_count) { UpdateBatVoltage(); } -void BAT::UpdateBatVoltage() { +void Battery::UpdateBatVoltage() { double cell_discharge_capasity = depth_of_discharge_percent_ / 100.0 * cell_capacity_Ah_; double temp = 0.0; int index = 0; diff --git a/src/components/real/power/battery.hpp b/src/components/real/power/battery.hpp index 5cfe8c473..e827e3c8c 100644 --- a/src/components/real/power/battery.hpp +++ b/src/components/real/power/battery.hpp @@ -12,13 +12,13 @@ #include "../../base/component.hpp" /* - * @class BAT + * @class Battery * @brief Component emulation of battery */ -class BAT : public Component, public ILoggable { +class Battery : public Component, public ILoggable { public: /** - * @fn BAT + * @fn Battery * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -32,11 +32,11 @@ class BAT : public Component, public ILoggable { * @param [in] battery_resistance_Ohm: Battery internal resistance [Ohm] * @param [in] component_step_time_s: Component step time [sec] */ - BAT(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, - const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, - double battery_resistance_Ohm, double component_step_time_s); + Battery(const int prescaler, ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm, double component_step_time_s); /** - * @fn BAT + * @fn Battery * @brief Constructor without prescaler * @note prescaler is set as 10 * @param [in] clock_generator: Clock generator @@ -49,19 +49,19 @@ class BAT : public Component, public ILoggable { * @param [in] cv_charge_voltage_V: Constant charge voltage [V] * @param [in] battery_resistance_Ohm: Battery internal resistance [Ohm] */ - BAT(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, - const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, - double battery_resistance_Ohm); + Battery(ClockGenerator* clock_generator, int number_of_series, int number_of_parallel, double cell_capacity_Ah, + const std::vector cell_discharge_curve_coefficients, double initial_dod, double cc_charge_c_rate, double cv_charge_voltage_V, + double battery_resistance_Ohm); /** - * @fn BAT + * @fn Battery * @brief Copy constructor */ - BAT(const BAT& obj); + Battery(const Battery& obj); /** - * @fn ~BAT + * @fn ~Battery * @brief Destructor */ - ~BAT(); + ~Battery(); /** * @fn SetChargeCurrent diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index 71b08501f..7b43d17a1 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -1,6 +1,6 @@ /* * @file initialize_battery.cpp - * @brief Initialize function of BAT + * @brief Initialize function of Battery */ #define _CRT_SECURE_NO_WARNINGS #include "initialize_battery.hpp" @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s) { +Battery InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s) { IniAccess bat_conf(file_name); const std::string st_bat_id = std::to_string(bat_id); @@ -52,8 +52,8 @@ BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_ double battery_resistance_Ohm; battery_resistance_Ohm = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); - BAT bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity_Ah, cell_discharge_curve_coefficients, initial_dod, - cc_charge_c_rate, cv_charge_voltage_V, battery_resistance_Ohm, component_step_time_s); + Battery bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity_Ah, cell_discharge_curve_coefficients, initial_dod, + cc_charge_c_rate, cv_charge_voltage_V, battery_resistance_Ohm, component_step_time_s); return bat; } diff --git a/src/components/real/power/initialize_battery.hpp b/src/components/real/power/initialize_battery.hpp index cb89d8747..7b3b4d682 100644 --- a/src/components/real/power/initialize_battery.hpp +++ b/src/components/real/power/initialize_battery.hpp @@ -1,6 +1,6 @@ /* * @file initialize_battery.hpp - * @brief Initialize function of BAT + * @brief Initialize function of Battery */ #ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ @@ -10,12 +10,12 @@ /* * @fn InitBAT - * @brief Initialize function of BAT + * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator * @param [in] bat_id: Battery ID * @param [in] file_name: Path to initialize file * @param [in] component_step_time_s: Component step time [sec] */ -BAT InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s); +Battery InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string file_name, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_BATTERY_HPP_ diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 28c9978ab..088a53105 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -11,8 +11,8 @@ #include "library/initialize/initialize_file_access.hpp" -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, - double component_step_time_s) { +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, + Battery* bat, double component_step_time_s) { IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index e6364848f..e4d6fdd44 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -10,7 +10,7 @@ /* * @fn InitPCU_InitialStudy - * @brief Initialize function of BAT + * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator * @param [in] pcu_id: Power Control Unit ID * @param [in] file_name: Path to initialize file @@ -18,7 +18,7 @@ * @param [in] bat: Battery information * @param [in] component_step_time_s: Component step time [sec] */ -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, BAT* bat, - double component_step_time_s); +PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, + Battery* bat, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index f3e783e4f..6c677acab 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -10,7 +10,7 @@ /* * @fn InitSAP - * @brief Initialize function of BAT + * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID * @param [in] file_name: Path to initialize file @@ -23,7 +23,7 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ /* * @fn InitSAP - * @brief Initialize function of BAT + * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator * @param [in] sap_id: SAP ID * @param [in] file_name: Path to initialize file diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index afa3423d4..774aa02a9 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -9,7 +9,7 @@ #include #include -PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, +PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* bat, double component_step_time_s) : Component(prescaler, clock_generator), saps_(saps), @@ -21,7 +21,7 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge power_consumption_ = 0.0; } -PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, BAT* bat) +PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* bat) : Component(10, clock_generator), saps_(saps), bat_(bat), diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index 7c194751d..3ef34206a 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -24,7 +24,7 @@ class PCU_InitialStudy : public Component, public ILoggable { * @param [in] bat: Battery * @param [in] component_step_time_s: Component step time [sec] */ - PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, BAT* bat, double component_step_time_s); + PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* bat, double component_step_time_s); /** * @fn PCU_InitialStudy * @brief Constructor @@ -32,7 +32,7 @@ class PCU_InitialStudy : public Component, public ILoggable { * @param [in] saps: Solar Array Panels * @param [in] bat: Battery */ - PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, BAT* bat); + PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* bat); /** * @fn ~PCU_InitialStudy * @brief Destructor @@ -53,7 +53,7 @@ class PCU_InitialStudy : public Component, public ILoggable { private: const std::vector saps_; //!< Solar Array Panels - BAT* const bat_; //!< Battery + Battery* const bat_; //!< Battery const double cc_charge_current_C_; //!< Constant charge current [C] const double cv_charge_voltage_V_; //!< Constant charge voltage [V] double bus_voltage_; //!< Bus voltage [V] From 9b0b3e965f3dc2fd9dafee3b3e510db6f60119aa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:56:20 +0100 Subject: [PATCH 0854/1086] Fix private variables name --- src/components/real/power/csv_scenario_interface.cpp | 6 +++--- src/components/real/power/csv_scenario_interface.hpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/power/csv_scenario_interface.cpp b/src/components/real/power/csv_scenario_interface.cpp index 4c999b0eb..1ed72c3d7 100644 --- a/src/components/real/power/csv_scenario_interface.cpp +++ b/src/components/real/power/csv_scenario_interface.cpp @@ -7,7 +7,7 @@ #include -bool CsvScenarioInterface::is_csv_senario_enabled_; +bool CsvScenarioInterface::is_csv_scenario_enabled_; std::map CsvScenarioInterface::buffer_line_id_; std::map CsvScenarioInterface::buffers_; @@ -15,7 +15,7 @@ void CsvScenarioInterface::Initialize(const std::string file_name) { IniAccess scenario_conf(file_name); char Section[30] = "SCENARIO"; - CsvScenarioInterface::is_csv_senario_enabled_ = scenario_conf.ReadBoolean(Section, "is_csv_scenario_enabled"); + CsvScenarioInterface::is_csv_scenario_enabled_ = scenario_conf.ReadBoolean(Section, "is_csv_scenario_enabled"); std::string csv_path; csv_path = scenario_conf.ReadString(Section, "csv_path"); @@ -34,7 +34,7 @@ void CsvScenarioInterface::Initialize(const std::string file_name) { } } -bool CsvScenarioInterface::IsCsvScenarioEnabled() { return CsvScenarioInterface::is_csv_senario_enabled_; } +bool CsvScenarioInterface::IsCsvScenarioEnabled() { return CsvScenarioInterface::is_csv_scenario_enabled_; } libra::Vector<3> CsvScenarioInterface::GetSunDirectionBody(const double time_query) { libra::Vector<3> sun_dir_b; diff --git a/src/components/real/power/csv_scenario_interface.hpp b/src/components/real/power/csv_scenario_interface.hpp index 6b9f1cadc..c98812a49 100644 --- a/src/components/real/power/csv_scenario_interface.hpp +++ b/src/components/real/power/csv_scenario_interface.hpp @@ -73,7 +73,7 @@ class CsvScenarioInterface { */ static double GetValueFromBuffer(const std::string buffer_name, const double time_query); - static bool is_csv_senario_enabled_; //!< Enable flag to use CSV scenario + static bool is_csv_scenario_enabled_; //!< Enable flag to use CSV scenario static std::map buffer_line_id_; //!< Buffer line ID static std::map buffers_; //!< Buffer }; From fc3a553e4a9e9a5de75477c1ba7a5365d42496c2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:57:40 +0100 Subject: [PATCH 0855/1086] Fix private variables nams --- .../real/power/initialize_battery.cpp | 6 +-- .../power/initialize_pcu_initial_study.cpp | 4 +- .../power/initialize_pcu_initial_study.hpp | 4 +- .../real/power/pcu_initial_study.cpp | 52 +++++++++---------- .../real/power/pcu_initial_study.hpp | 15 +++--- 5 files changed, 41 insertions(+), 40 deletions(-) diff --git a/src/components/real/power/initialize_battery.cpp b/src/components/real/power/initialize_battery.cpp index 7b43d17a1..72e66f63b 100644 --- a/src/components/real/power/initialize_battery.cpp +++ b/src/components/real/power/initialize_battery.cpp @@ -52,8 +52,8 @@ Battery InitBAT(ClockGenerator* clock_generator, int bat_id, const std::string f double battery_resistance_Ohm; battery_resistance_Ohm = bat_conf.ReadDouble(Section, "battery_resistance_Ohm"); - Battery bat(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity_Ah, cell_discharge_curve_coefficients, initial_dod, - cc_charge_c_rate, cv_charge_voltage_V, battery_resistance_Ohm, component_step_time_s); + Battery battery(prescaler, clock_generator, number_of_series, number_of_parallel, cell_capacity_Ah, cell_discharge_curve_coefficients, initial_dod, + cc_charge_c_rate, cv_charge_voltage_V, battery_resistance_Ohm, component_step_time_s); - return bat; + return battery; } diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 088a53105..17b6ae4e9 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -12,7 +12,7 @@ #include "library/initialize/initialize_file_access.hpp" PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* bat, double component_step_time_s) { + Battery* battery, double component_step_time_s) { IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); @@ -24,7 +24,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_i int prescaler = pcu_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - PCU_InitialStudy pcu(prescaler, clock_generator, saps, bat, component_step_time_s); + PCU_InitialStudy pcu(prescaler, clock_generator, saps, battery, component_step_time_s); return pcu; } diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index e4d6fdd44..279c0b4ea 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -15,10 +15,10 @@ * @param [in] pcu_id: Power Control Unit ID * @param [in] file_name: Path to initialize file * @param [in] sap: Solar Array Panel infomation - * @param [in] bat: Battery information + * @param [in] battery: Battery information * @param [in] component_step_time_s: Component step time [sec] */ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* bat, double component_step_time_s); + Battery* battery, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 774aa02a9..0b3814f9c 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -9,27 +9,27 @@ #include #include -PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* bat, +PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, double component_step_time_s) : Component(prescaler, clock_generator), saps_(saps), - bat_(bat), - cc_charge_current_C_(bat->GetCcChargeCurrent_C()), - cv_charge_voltage_V_(bat->GetCvChargeVoltage_V()), + battery_(battery), + cc_charge_current_C_(battery->GetCcChargeCurrent_C()), + cv_charge_voltage_V_(battery->GetCvChargeVoltage_V()), compo_step_time_s_(component_step_time_s) { - bus_voltage_ = 0.0; - power_consumption_ = 0.0; + bus_voltage_V_ = 0.0; + power_consumption_W_ = 0.0; } -PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* bat) +PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery) : Component(10, clock_generator), saps_(saps), - bat_(bat), - cc_charge_current_C_(bat->GetCcChargeCurrent_C()), - cv_charge_voltage_V_(bat->GetCvChargeVoltage_V()), + battery_(battery), + cc_charge_current_C_(battery->GetCcChargeCurrent_C()), + cv_charge_voltage_V_(battery->GetCvChargeVoltage_V()), compo_step_time_s_(0.1) { - bus_voltage_ = 0.0; - power_consumption_ = 0.0; + bus_voltage_V_ = 0.0; + power_consumption_W_ = 0.0; } PCU_InitialStudy::~PCU_InitialStudy() {} @@ -44,14 +44,14 @@ std::string PCU_InitialStudy::GetLogHeader() const { std::string PCU_InitialStudy::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(power_consumption_); - str_tmp += WriteScalar(bus_voltage_); + str_tmp += WriteScalar(power_consumption_W_); + str_tmp += WriteScalar(bus_voltage_V_); return str_tmp; } void PCU_InitialStudy::MainRoutine(int time_count) { double time_query = compo_step_time_s_ * time_count; - power_consumption_ = CalcPowerConsumption(time_query); // Should use SimulationTime? time_count may over flow since it is int type, + power_consumption_W_ = CalcPowerConsumption(time_query); // Should use SimulationTime? time_count may over flow since it is int type, UpdateChargeCurrentAndBusVoltage(); for (auto sap : saps_) { @@ -78,34 +78,34 @@ double PCU_InitialStudy::CalcPowerConsumption(double time_query) const { } void PCU_InitialStudy::UpdateChargeCurrentAndBusVoltage() { - double bat_voltage = bat_->GetVoltage_V(); - const double battery_resistance_Ohm = bat_->GetResistance_Ohm(); + double bat_voltage = battery_->GetVoltage_V(); + const double battery_resistance_Ohm = battery_->GetResistance_Ohm(); double power_generation = 0.0; for (auto sap : saps_) { power_generation += sap->GetPowerGeneration(); } double current_temp = - (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * battery_resistance_Ohm * (power_generation - power_consumption_))) / + (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * battery_resistance_Ohm * (power_generation - power_consumption_W_))) / (2.0 * battery_resistance_Ohm); if (current_temp >= cc_charge_current_C_) { if (bat_voltage + cc_charge_current_C_ * battery_resistance_Ohm < cv_charge_voltage_V_) { // CC Charge - bat_->SetChargeCurrent(cc_charge_current_C_); - bus_voltage_ = bat_voltage + battery_resistance_Ohm * cc_charge_current_C_; + battery_->SetChargeCurrent(cc_charge_current_C_); + bus_voltage_V_ = bat_voltage + battery_resistance_Ohm * cc_charge_current_C_; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); - bus_voltage_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; + battery_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); + bus_voltage_V_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; } } else { if (bat_voltage + current_temp * battery_resistance_Ohm < cv_charge_voltage_V_) { // Natural charge or discharge - bat_->SetChargeCurrent(current_temp); - bus_voltage_ = bat_voltage + battery_resistance_Ohm * current_temp; + battery_->SetChargeCurrent(current_temp); + bus_voltage_V_ = bat_voltage + battery_resistance_Ohm * current_temp; } else { // CV Charge - bat_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); - bus_voltage_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; + battery_->SetChargeCurrent((cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm); + bus_voltage_V_ = bat_voltage + battery_resistance_Ohm * (cv_charge_voltage_V_ - bat_voltage) / battery_resistance_Ohm; } } } diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index 3ef34206a..6e16c96d7 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -21,18 +21,19 @@ class PCU_InitialStudy : public Component, public ILoggable { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels - * @param [in] bat: Battery + * @param [in] battery: Battery * @param [in] component_step_time_s: Component step time [sec] */ - PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* bat, double component_step_time_s); + PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, + double component_step_time_s); /** * @fn PCU_InitialStudy * @brief Constructor * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels - * @param [in] bat: Battery + * @param [in] battery: Battery */ - PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* bat); + PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery); /** * @fn ~PCU_InitialStudy * @brief Destructor @@ -53,11 +54,11 @@ class PCU_InitialStudy : public Component, public ILoggable { private: const std::vector saps_; //!< Solar Array Panels - Battery* const bat_; //!< Battery + Battery* const battery_; //!< Battery const double cc_charge_current_C_; //!< Constant charge current [C] const double cv_charge_voltage_V_; //!< Constant charge voltage [V] - double bus_voltage_; //!< Bus voltage [V] - double power_consumption_; //!< Power consumption [W] + double bus_voltage_V_; //!< Bus voltage [V] + double power_consumption_W_; //!< Power consumption [W] double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component From b1a680cd64d61a134f4fcc77605763db96be415e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 11:58:09 +0100 Subject: [PATCH 0856/1086] Rename PCU_InitialStudy to PcuInitialStudy --- .../power/initialize_pcu_initial_study.cpp | 8 ++++---- .../power/initialize_pcu_initial_study.hpp | 6 +++--- .../real/power/pcu_initial_study.cpp | 18 +++++++++--------- .../real/power/pcu_initial_study.hpp | 15 +++++++-------- 4 files changed, 23 insertions(+), 24 deletions(-) diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 17b6ae4e9..4c014c5eb 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -1,6 +1,6 @@ /* * @file initialize_pcu_initial_study.cpp - * @brief Initialize function of PCU_InitialStudy + * @brief Initialize function of PcuInitialStudy */ #define _CRT_SECURE_NO_WARNINGS @@ -11,8 +11,8 @@ #include "library/initialize/initialize_file_access.hpp" -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* battery, double component_step_time_s) { +PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, + Battery* battery, double component_step_time_s) { IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); @@ -24,7 +24,7 @@ PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_i int prescaler = pcu_conf.ReadInt(Section, "prescaler"); if (prescaler <= 1) prescaler = 1; - PCU_InitialStudy pcu(prescaler, clock_generator, saps, battery, component_step_time_s); + PcuInitialStudy pcu(prescaler, clock_generator, saps, battery, component_step_time_s); return pcu; } diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index 279c0b4ea..cff4a960f 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -1,6 +1,6 @@ /* * @file initialize_pcu_initial_study.hpp - * @brief Initialize function of PCU_InitialStudy + * @brief Initialize function of PcuInitialStudy */ #ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ @@ -18,7 +18,7 @@ * @param [in] battery: Battery information * @param [in] component_step_time_s: Component step time [sec] */ -PCU_InitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* battery, double component_step_time_s); +PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, + Battery* battery, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index 0b3814f9c..f2d154cfa 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -9,8 +9,8 @@ #include #include -PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, - double component_step_time_s) +PcuInitialStudy::PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, + double component_step_time_s) : Component(prescaler, clock_generator), saps_(saps), battery_(battery), @@ -21,7 +21,7 @@ PCU_InitialStudy::PCU_InitialStudy(const int prescaler, ClockGenerator* clock_ge power_consumption_W_ = 0.0; } -PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery) +PcuInitialStudy::PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery) : Component(10, clock_generator), saps_(saps), battery_(battery), @@ -32,9 +32,9 @@ PCU_InitialStudy::PCU_InitialStudy(ClockGenerator* clock_generator, const std::v power_consumption_W_ = 0.0; } -PCU_InitialStudy::~PCU_InitialStudy() {} +PcuInitialStudy::~PcuInitialStudy() {} -std::string PCU_InitialStudy::GetLogHeader() const { +std::string PcuInitialStudy::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "pcu_initial_study_"; str_tmp += WriteScalar(component_name + "power_consumption", "W"); @@ -42,14 +42,14 @@ std::string PCU_InitialStudy::GetLogHeader() const { return str_tmp; } -std::string PCU_InitialStudy::GetLogValue() const { +std::string PcuInitialStudy::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(power_consumption_W_); str_tmp += WriteScalar(bus_voltage_V_); return str_tmp; } -void PCU_InitialStudy::MainRoutine(int time_count) { +void PcuInitialStudy::MainRoutine(int time_count) { double time_query = compo_step_time_s_ * time_count; power_consumption_W_ = CalcPowerConsumption(time_query); // Should use SimulationTime? time_count may over flow since it is int type, @@ -59,7 +59,7 @@ void PCU_InitialStudy::MainRoutine(int time_count) { } } -double PCU_InitialStudy::CalcPowerConsumption(double time_query) const { +double PcuInitialStudy::CalcPowerConsumption(double time_query) const { if (CsvScenarioInterface::IsCsvScenarioEnabled()) { return CsvScenarioInterface::GetPowerConsumption(time_query); } else { @@ -77,7 +77,7 @@ double PCU_InitialStudy::CalcPowerConsumption(double time_query) const { } } -void PCU_InitialStudy::UpdateChargeCurrentAndBusVoltage() { +void PcuInitialStudy::UpdateChargeCurrentAndBusVoltage() { double bat_voltage = battery_->GetVoltage_V(); const double battery_resistance_Ohm = battery_->GetResistance_Ohm(); double power_generation = 0.0; diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index 6e16c96d7..0f837aa33 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -13,10 +13,10 @@ #include "battery.hpp" #include "solar_array_panel.hpp" -class PCU_InitialStudy : public Component, public ILoggable { +class PcuInitialStudy : public Component, public ILoggable { public: /** - * @fn PCU_InitialStudy + * @fn PcuInitialStudy * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -24,21 +24,20 @@ class PCU_InitialStudy : public Component, public ILoggable { * @param [in] battery: Battery * @param [in] component_step_time_s: Component step time [sec] */ - PCU_InitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, - double component_step_time_s); + PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, double component_step_time_s); /** - * @fn PCU_InitialStudy + * @fn PcuInitialStudy * @brief Constructor * @param [in] clock_generator: Clock generator * @param [in] saps: Solar Array Panels * @param [in] battery: Battery */ - PCU_InitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery); + PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery); /** - * @fn ~PCU_InitialStudy + * @fn ~PcuInitialStudy * @brief Destructor */ - ~PCU_InitialStudy(); + ~PcuInitialStudy(); // Override ILoggable /** From 0039795ae871f9f137327f5dd28e6f4e069f488f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 12:00:16 +0100 Subject: [PATCH 0857/1086] Fix private variables names --- .../real/power/power_control_unit.cpp | 20 +++++++++---------- .../real/power/power_control_unit.hpp | 6 +++--- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index 4a087cc13..a8f220d65 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -10,35 +10,35 @@ PCU::PCU(int prescaler, ClockGenerator* clock_generator) : Component(prescaler, PCU::~PCU() {} -void PCU::MainRoutine(int count) { - UNUSED(count); +void PCU::MainRoutine(const int time_count) { + UNUSED(time_count); - // double current_ = ports_[1]->GetCurrentConsumption_A(); + // double current_ = power_ports_[1]->GetCurrentConsumption_A(); } int PCU::ConnectPort(const int port_id, const double current_Limit) { // The port is already used - if (ports_[port_id] != nullptr) return -1; + if (power_ports_[port_id] != nullptr) return -1; - ports_[port_id] = new PowerPort(port_id, current_Limit); + power_ports_[port_id] = new PowerPort(port_id, current_Limit); return 0; } int PCU::ConnectPort(const int port_id, const double current_Limit, const double minimum_voltage, const double assumed_power_consumption) { // The port is already used - if (ports_[port_id] != nullptr) return -1; + if (power_ports_[port_id] != nullptr) return -1; - ports_[port_id] = new PowerPort(port_id, current_Limit, minimum_voltage, assumed_power_consumption); + power_ports_[port_id] = new PowerPort(port_id, current_Limit, minimum_voltage, assumed_power_consumption); return 0; } int PCU::ClosePort(const int port_id) { // The port not used - if (ports_[port_id] == nullptr) return -1; + if (power_ports_[port_id] == nullptr) return -1; - PowerPort* port = ports_.at(port_id); + PowerPort* port = power_ports_.at(port_id); delete port; - ports_.erase(port_id); + power_ports_.erase(port_id); return 0; } diff --git a/src/components/real/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp index 431030437..41825eafb 100644 --- a/src/components/real/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -42,7 +42,7 @@ class PCU : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int count) override; + void MainRoutine(const int time_count) override; // Override ILoggable /** @@ -61,7 +61,7 @@ class PCU : public Component, public ILoggable { * @brief Return power port information * @param port_id: Power port ID */ - inline PowerPort* GetPowerPort(int port_id) { return ports_[port_id]; }; + inline PowerPort* GetPowerPort(int port_id) { return power_ports_[port_id]; }; // Port control functions /** @@ -91,7 +91,7 @@ class PCU : public Component, public ILoggable { int ClosePort(const int port_id); private: - std::map ports_; //!< Power port list + std::map power_ports_; //!< Power port list }; #endif // S2E_COMPONENTS_REAL_POWER_POWER_CONTROL_UNIT_HPP_ From 4b954979c9d08085791b2d9babd8732b135ddbbd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:11:39 +0100 Subject: [PATCH 0858/1086] Fix function argument name --- src/components/real/cdh/on_board_computer.cpp | 5 +++-- src/components/real/cdh/on_board_computer.hpp | 4 ++-- src/components/real/power/power_control_unit.cpp | 8 ++++---- src/components/real/power/power_control_unit.hpp | 12 ++++++------ 4 files changed, 15 insertions(+), 14 deletions(-) diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index 1fe82fa09..c22accdd4 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -8,9 +8,10 @@ OBC::OBC(ClockGenerator* clock_generator) : Component(1, clock_generator) { Init OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port) : Component(prescaler, clock_generator, power_port) { Initialize(); } -OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption) +OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, + const double assumed_power_consumption) : Component(prescaler, clock_generator, power_port) { - power_port_->SetMinimumVoltage_V(minimum_voltage); + power_port_->SetMinimumVoltage_V(minimum_voltage_V); power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption); Initialize(); } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 123a1de22..6d4d32bef 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -40,10 +40,10 @@ class OBC : public Component { * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port - * @param [in] minimum_voltage: Minimum voltage [V] + * @param [in] minimum_voltage_V: Minimum voltage [V] * @param [in] assumed_power_consumption: Assumed power consumption [W] */ - OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage, const double assumed_power_consumption); + OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, const double assumed_power_consumption); /** * @fn ~OBC * @brief Destructor diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index a8f220d65..011aa6972 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -16,19 +16,19 @@ void PCU::MainRoutine(const int time_count) { // double current_ = power_ports_[1]->GetCurrentConsumption_A(); } -int PCU::ConnectPort(const int port_id, const double current_Limit) { +int PCU::ConnectPort(const int port_id, const double current_limit_A) { // The port is already used if (power_ports_[port_id] != nullptr) return -1; - power_ports_[port_id] = new PowerPort(port_id, current_Limit); + power_ports_[port_id] = new PowerPort(port_id, current_limit_A); return 0; } -int PCU::ConnectPort(const int port_id, const double current_Limit, const double minimum_voltage, const double assumed_power_consumption) { +int PCU::ConnectPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W) { // The port is already used if (power_ports_[port_id] != nullptr) return -1; - power_ports_[port_id] = new PowerPort(port_id, current_Limit, minimum_voltage, assumed_power_consumption); + power_ports_[port_id] = new PowerPort(port_id, current_limit_A, minimum_voltage_V, assumed_power_consumption_W); return 0; } diff --git a/src/components/real/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp index 41825eafb..f6c513789 100644 --- a/src/components/real/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -68,20 +68,20 @@ class PCU : public Component, public ILoggable { * @fn ConnectPort * @brief Connect power port between components and PCU * @param port_id: Power port ID - * @param [in] current_Limit: Threshold to detect over current [A] + * @param [in] current_limit_A: Threshold to detect over current [A] * @return 0: Success, -1: Error */ - int ConnectPort(const int port_id, const double current_Limit); + int ConnectPort(const int port_id, const double current_limit_A); /** * @fn ConnectPort * @brief Connect power port between components and PCU * @param port_id: Power port ID - * @param [in] current_Limit: Threshold to detect over current [A] - * @param [in] minimum_voltage: Minimum voltage to work the component [V] - * @param [in] assumed_power_consumption: Assumed power consumption of the component [W] + * @param [in] current_limit_A: Threshold to detect over current [A] + * @param [in] minimum_voltage_V: Minimum voltage to work the component [V] + * @param [in] assumed_power_consumption_W: Assumed power consumption of the component [W] * @return 0: Success, -1: Error */ - int ConnectPort(const int port_id, const double current_Limit, const double minimum_voltage, const double assumed_power_consumption); + int ConnectPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W); /** * @fn ClosePort * @brief Close power port between components and PCU From 5769da825b70d75e97133e37a01bd30a00bbf0c9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:14:36 +0100 Subject: [PATCH 0859/1086] Rename PCU to PowerControlUnit --- .../real/power/power_control_unit.cpp | 19 ++++++++------- .../real/power/power_control_unit.hpp | 24 +++++++++---------- .../sample_spacecraft/sample_components.cpp | 2 +- .../sample_spacecraft/sample_components.hpp | 4 ++-- 4 files changed, 25 insertions(+), 24 deletions(-) diff --git a/src/components/real/power/power_control_unit.cpp b/src/components/real/power/power_control_unit.cpp index 011aa6972..055300e2c 100644 --- a/src/components/real/power/power_control_unit.cpp +++ b/src/components/real/power/power_control_unit.cpp @@ -4,19 +4,19 @@ */ #include "power_control_unit.hpp" -PCU::PCU(ClockGenerator* clock_generator) : Component(1, clock_generator) {} +PowerControlUnit::PowerControlUnit(ClockGenerator* clock_generator) : Component(1, clock_generator) {} -PCU::PCU(int prescaler, ClockGenerator* clock_generator) : Component(prescaler, clock_generator) {} +PowerControlUnit::PowerControlUnit(int prescaler, ClockGenerator* clock_generator) : Component(prescaler, clock_generator) {} -PCU::~PCU() {} +PowerControlUnit::~PowerControlUnit() {} -void PCU::MainRoutine(const int time_count) { +void PowerControlUnit::MainRoutine(const int time_count) { UNUSED(time_count); // double current_ = power_ports_[1]->GetCurrentConsumption_A(); } -int PCU::ConnectPort(const int port_id, const double current_limit_A) { +int PowerControlUnit::ConnectPort(const int port_id, const double current_limit_A) { // The port is already used if (power_ports_[port_id] != nullptr) return -1; @@ -24,7 +24,8 @@ int PCU::ConnectPort(const int port_id, const double current_limit_A) { return 0; } -int PCU::ConnectPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W) { +int PowerControlUnit::ConnectPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, + const double assumed_power_consumption_W) { // The port is already used if (power_ports_[port_id] != nullptr) return -1; @@ -32,7 +33,7 @@ int PCU::ConnectPort(const int port_id, const double current_limit_A, const doub return 0; } -int PCU::ClosePort(const int port_id) { +int PowerControlUnit::ClosePort(const int port_id) { // The port not used if (power_ports_[port_id] == nullptr) return -1; @@ -42,12 +43,12 @@ int PCU::ClosePort(const int port_id) { return 0; } -std::string PCU::GetLogHeader() const { +std::string PowerControlUnit::GetLogHeader() const { std::string str_tmp = ""; return str_tmp; } -std::string PCU::GetLogValue() const { +std::string PowerControlUnit::GetLogValue() const { std::string str_tmp = ""; return str_tmp; } diff --git a/src/components/real/power/power_control_unit.hpp b/src/components/real/power/power_control_unit.hpp index f6c513789..efb75b98e 100644 --- a/src/components/real/power/power_control_unit.hpp +++ b/src/components/real/power/power_control_unit.hpp @@ -13,29 +13,29 @@ #include "../../base/component.hpp" /* - * @class PCU + * @class PowerControlUnit * @brief Component emulation of Power Control Unit */ -class PCU : public Component, public ILoggable { +class PowerControlUnit : public Component, public ILoggable { public: /** - * @fn PCU + * @fn PowerControlUnit * @brief Constructor * @param [in] clock_generator: Clock generator */ - PCU(ClockGenerator* clock_generator); + PowerControlUnit(ClockGenerator* clock_generator); /** - * @fn PCU + * @fn PowerControlUnit * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator */ - PCU(int prescaler, ClockGenerator* clock_generator); + PowerControlUnit(int prescaler, ClockGenerator* clock_generator); /** - * @fn ~PCU + * @fn ~PowerControlUnit * @brief Destructor */ - ~PCU(); + ~PowerControlUnit(); // Override functions for Component /** @@ -61,12 +61,12 @@ class PCU : public Component, public ILoggable { * @brief Return power port information * @param port_id: Power port ID */ - inline PowerPort* GetPowerPort(int port_id) { return power_ports_[port_id]; }; + inline PowerPort* GetPowerPort(const int port_id) { return power_ports_[port_id]; }; // Port control functions /** * @fn ConnectPort - * @brief Connect power port between components and PCU + * @brief Connect power port between components and PowerControlUnit * @param port_id: Power port ID * @param [in] current_limit_A: Threshold to detect over current [A] * @return 0: Success, -1: Error @@ -74,7 +74,7 @@ class PCU : public Component, public ILoggable { int ConnectPort(const int port_id, const double current_limit_A); /** * @fn ConnectPort - * @brief Connect power port between components and PCU + * @brief Connect power port between components and PowerControlUnit * @param port_id: Power port ID * @param [in] current_limit_A: Threshold to detect over current [A] * @param [in] minimum_voltage_V: Minimum voltage to work the component [V] @@ -84,7 +84,7 @@ class PCU : public Component, public ILoggable { int ConnectPort(const int port_id, const double current_limit_A, const double minimum_voltage_V, const double assumed_power_consumption_W); /** * @fn ClosePort - * @brief Close power port between components and PCU + * @brief Close power port between components and PowerControlUnit * @param port_id: Power port ID * @return 0: Success, -1: Error */ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 0a0d0819e..05d3344fe 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -15,7 +15,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur IniAccess iniAccess = IniAccess(config_->sat_file_[sat_id]); // PCU power port connection - pcu_ = new PCU(clock_gen); + pcu_ = new PowerControlUnit(clock_gen); pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyroSensor pcu_->ConnectPort(2, 1.0); // for other all components diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 2a9b8718e..5f2a8bbfe 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -31,7 +31,7 @@ #include "../installed_components.hpp" class OBC; -class PCU; +class PowerControlUnit; class GyroSensor; class Magnetometer; class StarSensor; @@ -82,7 +82,7 @@ class SampleComponents : public InstalledComponents { inline Antenna& GetAntenna() const { return *antenna_; } private: - PCU* pcu_; //!< Power Control Unit + PowerControlUnit* pcu_; //!< Power Control Unit OBC* obc_; //!< Onboard Computer HilsPortManager* hils_port_manager_; //!< Port manager for HILS test From 33d9f17c8c415d626cd7d825dec05a1c758cdc7f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:26:11 +0100 Subject: [PATCH 0860/1086] Fix function argument names --- src/components/real/aocs/sun_sensor.cpp | 8 +-- src/components/real/aocs/sun_sensor.hpp | 2 +- .../real/power/solar_array_panel.cpp | 54 +++++++++---------- .../real/power/solar_array_panel.hpp | 14 ++--- 4 files changed, 39 insertions(+), 39 deletions(-) diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 88650648d..2cf370e5c 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -22,7 +22,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), - srp_(srp), + srp_environment_(srp), local_celestial_information_(local_celestial_information) { Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } @@ -36,7 +36,7 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, Power quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), - srp_(srp), + srp_environment_(srp), local_celestial_information_(local_celestial_information) { Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } @@ -99,7 +99,7 @@ void SunSensor::SunDetectionJudgement() { double sun_angle_ = acos(sun_direction_c[2]); - if (solar_illuminance_W_m2_ < intensity_lower_threshold_percent_ / 100.0 * srp_->GetSolarConstant_W_m2()) { + if (solar_illuminance_W_m2_ < intensity_lower_threshold_percent_ / 100.0 * srp_environment_->GetSolarConstant_W_m2()) { sun_detected_flag_ = false; } else { if (sun_angle_ < detectable_angle_rad_) { @@ -119,7 +119,7 @@ void SunSensor::CalcSolarIlluminance() { return; } - double power_density = srp_->GetPowerDensity_W_m2(); + double power_density = srp_environment_->GetPowerDensity_W_m2(); solar_illuminance_W_m2_ = power_density * cos(sun_angle_); // TODO: Take into account the effects of albedo. } diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index dfbdadaf3..8a28adc42 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -106,7 +106,7 @@ class SunSensor : public Component, public ILoggable { double bias_noise_beta_rad_ = 0.0; //!< Constant bias for beta angle (Value is calculated by random number generator) // Measured variables - const SolarRadiationPressureEnvironment* srp_; //!< Solar Radiation Pressure environment + const SolarRadiationPressureEnvironment* srp_environment_; //!< Solar Radiation Pressure environment const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information // functions diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index b79cd5d15..2050586ba 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -15,15 +15,15 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_(cell_area), + cell_area_m2_(cell_area), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_(srp), + srp_environment_(srp), local_celestial_information_(local_celestial_information), compo_step_time_s_(component_step_time_s) { - voltage_ = 0.0; - power_generation_ = 0.0; + voltage_V_ = 0.0; + power_generation_W_ = 0.0; } SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, @@ -33,14 +33,14 @@ SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_(cell_area), + cell_area_m2_(cell_area), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_(srp), + srp_environment_(srp), compo_step_time_s_(component_step_time_s) { - voltage_ = 0.0; - power_generation_ = 0.0; + voltage_V_ = 0.0; + power_generation_W_ = 0.0; } SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, @@ -50,15 +50,15 @@ SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_(cell_area), + cell_area_m2_(cell_area), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_(srp), + srp_environment_(srp), local_celestial_information_(local_celestial_information), compo_step_time_s_(0.1) { - voltage_ = 0.0; - power_generation_ = 0.0; + voltage_V_ = 0.0; + power_generation_W_ = 0.0; } SAP::SAP(const SAP& obj) @@ -66,22 +66,22 @@ SAP::SAP(const SAP& obj) component_id_(obj.component_id_), number_of_series_(obj.number_of_series_), number_of_parallel_(obj.number_of_parallel_), - cell_area_(obj.cell_area_), + cell_area_m2_(obj.cell_area_m2_), normal_vector_(obj.normal_vector_), cell_efficiency_(obj.cell_efficiency_), transmission_efficiency_(obj.transmission_efficiency_), - srp_(obj.srp_), + srp_environment_(obj.srp_environment_), local_celestial_information_(obj.local_celestial_information_), compo_step_time_s_(obj.compo_step_time_s_) { - voltage_ = 0.0; - power_generation_ = 0.0; + voltage_V_ = 0.0; + power_generation_W_ = 0.0; } SAP::~SAP() {} -double SAP::GetPowerGeneration() const { return power_generation_; } +double SAP::GetPowerGeneration() const { return power_generation_W_; } -void SAP::SetVoltage_V(const double voltage) { voltage_ = voltage; } +void SAP::SetVoltage_V(const double voltage) { voltage_V_ = voltage; } std::string SAP::GetLogHeader() const { std::string str_tmp = ""; @@ -92,25 +92,25 @@ std::string SAP::GetLogHeader() const { std::string SAP::GetLogValue() const { std::string str_tmp = ""; - str_tmp += WriteScalar(power_generation_); + str_tmp += WriteScalar(power_generation_W_); return str_tmp; } -void SAP::MainRoutine(int time_count) { +void SAP::MainRoutine(const int time_count) { if (CsvScenarioInterface::IsCsvScenarioEnabled()) { double time_query = compo_step_time_s_ * time_count; - const auto solar_constant = srp_->GetSolarConstant_W_m2(); + const auto solar_constant = srp_environment_->GetSolarConstant_W_m2(); libra::Vector<3> sun_direction_body = CsvScenarioInterface::GetSunDirectionBody(time_query); libra::Vector<3> normalized_sun_direction_body = libra::Normalize(sun_direction_body); - power_generation_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * - cell_area_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, normalized_sun_direction_body); + power_generation_W_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * + cell_area_m2_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, normalized_sun_direction_body); } else { - const auto power_density = srp_->GetPowerDensity_W_m2(); + const auto power_density = srp_environment_->GetPowerDensity_W_m2(); libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); libra::Vector<3> sun_dir_b = libra::Normalize(sun_pos_b); - power_generation_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_ * number_of_parallel_ * number_of_series_ * - InnerProduct(normal_vector_, sun_dir_b); + power_generation_W_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_m2_ * number_of_parallel_ * number_of_series_ * + InnerProduct(normal_vector_, sun_dir_b); // TODO: Improve implementation. For example, update IV curve with sun direction and calculate generated power } - if (power_generation_ < 0) power_generation_ = 0.0; + if (power_generation_W_ < 0) power_generation_W_ = 0.0; } diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 38282044a..106476e27 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -108,27 +108,27 @@ class SAP : public Component, public ILoggable { const int component_id_; //!< SAP ID TODO: Use string? const int number_of_series_; //!< Number of series connected solar cells const int number_of_parallel_; //!< Number of parallel connected solar cells - const double cell_area_; //!< Solar cell area [m^2] + const double cell_area_m2_; //!< Solar cell area [m^2] const libra::Vector<3> normal_vector_; //!< Normal vector of SAP on the body fixed frame const double cell_efficiency_; //!< Power generation efficiency of solar cell const double transmission_efficiency_; //!< Efficiency of transmission to PCU - const SolarRadiationPressureEnvironment* const srp_; //!< Solar Radiation Pressure environment - const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information + const SolarRadiationPressureEnvironment* const srp_environment_; //!< Solar Radiation Pressure environment + const LocalCelestialInformation* local_celestial_information_; //!< Local celestial information - double voltage_; //!< Voltage [V] - double power_generation_; //!< Generated power [W] + double voltage_V_; //!< Voltage [V] + double power_generation_W_; //!< Generated power [W] static const double solar_constant_; //!< Solar constant TODO: Use SolarRadiationPressureEnvironment? static const double light_speed_; //!< Speed of light TODO: Use PhysicalConstant? - double compo_step_time_s_; //!< Component step time [sec] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int time_count) override; + void MainRoutine(const int time_count) override; }; #endif // S2E_COMPONENTS_REAL_POWER_SOLAR_ARRAY_PANEL_HPP_ From 0745115b2e7c529d0d6427936ceabd91dc8c97ff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:26:48 +0100 Subject: [PATCH 0861/1086] Delete unused private variables --- src/components/real/power/solar_array_panel.hpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 106476e27..67b4c5972 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -119,9 +119,7 @@ class SAP : public Component, public ILoggable { double voltage_V_; //!< Voltage [V] double power_generation_W_; //!< Generated power [W] - static const double solar_constant_; //!< Solar constant TODO: Use SolarRadiationPressureEnvironment? - static const double light_speed_; //!< Speed of light TODO: Use PhysicalConstant? - double compo_step_time_s_; //!< Component step time [sec] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** From 4a0b655e3727d0e04ed159ed00bd95765638a3e8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:32:13 +0100 Subject: [PATCH 0862/1086] Rename SAP to SolarArrayPanel --- .../real/aocs/initialize_sun_sensor.cpp | 8 +-- .../real/aocs/initialize_sun_sensor.hpp | 10 +-- src/components/real/aocs/sun_sensor.cpp | 8 +-- src/components/real/aocs/sun_sensor.hpp | 8 +-- .../power/initialize_pcu_initial_study.cpp | 4 +- .../power/initialize_pcu_initial_study.hpp | 4 +- .../power/initialize_solar_array_panel.cpp | 27 +++---- .../power/initialize_solar_array_panel.hpp | 19 ++--- .../real/power/pcu_initial_study.cpp | 6 +- .../real/power/pcu_initial_study.hpp | 19 ++--- .../real/power/solar_array_panel.cpp | 46 ++++++------ .../real/power/solar_array_panel.hpp | 70 ++++++++++--------- src/dynamics/thermal/initialize_node.cpp | 2 +- 13 files changed, 117 insertions(+), 114 deletions(-) diff --git a/src/components/real/aocs/initialize_sun_sensor.cpp b/src/components/real/aocs/initialize_sun_sensor.cpp index b9e5bbb24..e9028e6e6 100644 --- a/src/components/real/aocs/initialize_sun_sensor.cpp +++ b/src/components/real/aocs/initialize_sun_sensor.cpp @@ -10,7 +10,7 @@ #include "library/initialize/initialize_file_access.hpp" -SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp, +SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string file_name, const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; @@ -39,12 +39,12 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int ss_id, std::string intensity_lower_threshold_percent = ss_conf.ReadDouble(Section, "intensity_lower_threshold_percent"); SunSensor ss(prescaler, clock_generator, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, intensity_lower_threshold_percent, - srp, local_celestial_information); + srp_environment, local_celestial_information); return ss; } SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int ss_id, std::string file_name, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) { + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information) { IniAccess ss_conf(file_name); const char* sensor_name = "SUN_SENSOR_"; const std::string section_tmp = sensor_name + std::to_string(static_cast(ss_id)); @@ -74,6 +74,6 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, power_port->InitializeWithInitializeFile(file_name); SunSensor ss(prescaler, clock_generator, power_port, ss_id, quaternion_b2c, detectable_angle_rad, nr_stddev, nr_bias_stddev, - intensity_lower_threshold_percent, srp, local_celestial_information); + intensity_lower_threshold_percent, srp_environment, local_celestial_information); return ss; } diff --git a/src/components/real/aocs/initialize_sun_sensor.hpp b/src/components/real/aocs/initialize_sun_sensor.hpp index be94bb1d2..b162f498e 100644 --- a/src/components/real/aocs/initialize_sun_sensor.hpp +++ b/src/components/real/aocs/initialize_sun_sensor.hpp @@ -14,11 +14,11 @@ * @param [in] clock_generator: Clock generator * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] srp: Solar radiation pressure environment + * @param [in] srp_environment: Solar radiation pressure environment * @param [in] local_environment: Local environment information */ -SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information); +SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const std::string file_name, + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information); /** * @fn InitSunSensor * @brief Initialize functions for sun sensor with power port @@ -26,10 +26,10 @@ SunSensor InitSunSensor(ClockGenerator* clock_generator, int sensor_id, const st * @param [in] power_port: Power port * @param [in] sensor_id: Sensor ID * @param [in] file_name: Path to the initialize file - * @param [in] srp: Solar radiation pressure environment + * @param [in] srp_environment: Solar radiation pressure environment * @param [in] local_environment: Local environment information */ SunSensor InitSunSensor(ClockGenerator* clock_generator, PowerPort* power_port, int sensor_id, const std::string file_name, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information); #endif // S2E_COMPONENTS_REAL_AOCS_INITIALIZE_SUN_SENSOR_HPP_ diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index 2cf370e5c..a3a18de7d 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -16,13 +16,13 @@ using namespace std; SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator), component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), - srp_environment_(srp), + srp_environment_(srp_environment), local_celestial_information_(local_celestial_information) { Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } @@ -30,13 +30,13 @@ SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, const SunSensor::SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information) + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information) : Component(prescaler, clock_generator, power_port), component_id_(component_id), quaternion_b2c_(quaternion_b2c), intensity_lower_threshold_percent_(intensity_lower_threshold_percent), detectable_angle_rad_(detectable_angle_rad), - srp_environment_(srp), + srp_environment_(srp_environment), local_celestial_information_(local_celestial_information) { Initialize(random_noise_standard_deviation_rad, bias_noise_standard_deviation_rad); } diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 8a28adc42..f6898a99c 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -32,12 +32,12 @@ class SunSensor : public Component, public ILoggable { * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, - const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp, + const double intensity_lower_threshold_percent, const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information); /** * @fn SunSensor @@ -51,13 +51,13 @@ class SunSensor : public Component, public ILoggable { * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] * @param [in] intensity_lower_threshold_percent: Solar intensity lower threshold [%] - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ SunSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, const libra::Quaternion& quaternion_b2c, const double detectable_angle_rad, const double random_noise_standard_deviation_rad, const double bias_noise_standard_deviation_rad, const double intensity_lower_threshold_percent, - const SolarRadiationPressureEnvironment* srp, const LocalCelestialInformation* local_celestial_information); + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information); // Override functions for Component /** diff --git a/src/components/real/power/initialize_pcu_initial_study.cpp b/src/components/real/power/initialize_pcu_initial_study.cpp index 4c014c5eb..65c061ec0 100644 --- a/src/components/real/power/initialize_pcu_initial_study.cpp +++ b/src/components/real/power/initialize_pcu_initial_study.cpp @@ -11,8 +11,8 @@ #include "library/initialize/initialize_file_access.hpp" -PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* battery, double component_step_time_s) { +PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, + const std::vector saps, Battery* battery, double component_step_time_s) { IniAccess pcu_conf(file_name); const std::string st_pcu_id = std::to_string(pcu_id); diff --git a/src/components/real/power/initialize_pcu_initial_study.hpp b/src/components/real/power/initialize_pcu_initial_study.hpp index cff4a960f..d11e0e0fa 100644 --- a/src/components/real/power/initialize_pcu_initial_study.hpp +++ b/src/components/real/power/initialize_pcu_initial_study.hpp @@ -18,7 +18,7 @@ * @param [in] battery: Battery information * @param [in] component_step_time_s: Component step time [sec] */ -PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, const std::vector saps, - Battery* battery, double component_step_time_s); +PcuInitialStudy InitPCU_InitialStudy(ClockGenerator* clock_generator, int pcu_id, const std::string file_name, + const std::vector saps, Battery* battery, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_PCU_INITIAL_STUDY_HPP_ diff --git a/src/components/real/power/initialize_solar_array_panel.cpp b/src/components/real/power/initialize_solar_array_panel.cpp index 0b556f057..0299ac2e1 100644 --- a/src/components/real/power/initialize_solar_array_panel.cpp +++ b/src/components/real/power/initialize_solar_array_panel.cpp @@ -1,6 +1,6 @@ /* * @file initialize_solar_array_panel.cpp - * @brief Initialize function of SAP (Solar Array Panel) + * @brief Initialize function of SolarArrayPanel (Solar Array Panel) */ #define _CRT_SECURE_NO_WARNINGS #include "initialize_solar_array_panel.hpp" @@ -9,8 +9,9 @@ #include "library/initialize/initialize_file_access.hpp" -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double component_step_time_s) { +SolarArrayPanel InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information, + double component_step_time_s) { IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); @@ -28,8 +29,8 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ int number_of_parallel; number_of_parallel = sap_conf.ReadInt(Section, "number_of_parallel"); - double cell_area; - cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); + double cell_area_m2; + cell_area_m2 = sap_conf.ReadDouble(Section, "cell_area_m2"); libra::Vector<3> normal_vector; sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); @@ -40,14 +41,14 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ double transmission_efficiency; transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); - SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, - transmission_efficiency, srp, local_celestial_information, component_step_time_s); + SolarArrayPanel sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area_m2, normal_vector, cell_efficiency, + transmission_efficiency, srp_environment, local_celestial_information, component_step_time_s); return sap; } -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - double component_step_time_s) { +SolarArrayPanel InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, + const SolarRadiationPressureEnvironment* srp_environment, double component_step_time_s) { IniAccess sap_conf(file_name); const std::string st_sap_id = std::to_string(sap_id); @@ -65,8 +66,8 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ int number_of_parallel; number_of_parallel = sap_conf.ReadInt(Section, "number_of_parallel"); - double cell_area; - cell_area = sap_conf.ReadDouble(Section, "cell_area_m2"); + double cell_area_m2; + cell_area_m2 = sap_conf.ReadDouble(Section, "cell_area_m2"); libra::Vector<3> normal_vector; sap_conf.ReadVector(Section, "normal_vector_b", normal_vector); @@ -77,8 +78,8 @@ SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_ double transmission_efficiency; transmission_efficiency = sap_conf.ReadDouble(Section, "transmission_efficiency"); - SAP sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area, normal_vector, cell_efficiency, - transmission_efficiency, srp, component_step_time_s); + SolarArrayPanel sap(prescaler, clock_generator, sap_id, number_of_series, number_of_parallel, cell_area_m2, normal_vector, cell_efficiency, + transmission_efficiency, srp_environment, component_step_time_s); return sap; } diff --git a/src/components/real/power/initialize_solar_array_panel.hpp b/src/components/real/power/initialize_solar_array_panel.hpp index 6c677acab..e7edff7ce 100644 --- a/src/components/real/power/initialize_solar_array_panel.hpp +++ b/src/components/real/power/initialize_solar_array_panel.hpp @@ -1,6 +1,6 @@ /* * @file initialize_solar_array_panel.hpp - * @brief Initialize function of SAP (Solar Array Panel) + * @brief Initialize function of SolarArrayPanel (Solar Array Panel) */ #ifndef S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ @@ -12,25 +12,26 @@ * @fn InitSAP * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator - * @param [in] sap_id: SAP ID + * @param [in] sap_id: SolarArrayPanel ID * @param [in] file_name: Path to initialize file - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information * @param [in] component_step_time_s: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double component_step_time_s); +SolarArrayPanel InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information, + double component_step_time_s); /* * @fn InitSAP * @brief Initialize function of Battery * @param [in] clock_generator: Clock generator - * @param [in] sap_id: SAP ID + * @param [in] sap_id: SolarArrayPanel ID * @param [in] file_name: Path to initialize file - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] component_step_time_s: Component step time [sec] */ -SAP InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, const SolarRadiationPressureEnvironment* srp, - double component_step_time_s); +SolarArrayPanel InitSAP(ClockGenerator* clock_generator, int sap_id, const std::string file_name, + const SolarRadiationPressureEnvironment* srp_environment, double component_step_time_s); #endif // S2E_COMPONENTS_REAL_POWER_INITIALIZE_SOLAR_ARRAY_PANEL_HPP_ diff --git a/src/components/real/power/pcu_initial_study.cpp b/src/components/real/power/pcu_initial_study.cpp index f2d154cfa..d9617c63f 100644 --- a/src/components/real/power/pcu_initial_study.cpp +++ b/src/components/real/power/pcu_initial_study.cpp @@ -9,7 +9,7 @@ #include #include -PcuInitialStudy::PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, +PcuInitialStudy::PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, double component_step_time_s) : Component(prescaler, clock_generator), saps_(saps), @@ -21,7 +21,7 @@ PcuInitialStudy::PcuInitialStudy(const int prescaler, ClockGenerator* clock_gene power_consumption_W_ = 0.0; } -PcuInitialStudy::PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery) +PcuInitialStudy::PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery) : Component(10, clock_generator), saps_(saps), battery_(battery), @@ -82,7 +82,7 @@ void PcuInitialStudy::UpdateChargeCurrentAndBusVoltage() { const double battery_resistance_Ohm = battery_->GetResistance_Ohm(); double power_generation = 0.0; for (auto sap : saps_) { - power_generation += sap->GetPowerGeneration(); + power_generation += sap->GetPowerGeneration_W(); } double current_temp = (-bat_voltage + std::sqrt(bat_voltage * bat_voltage + 4.0 * battery_resistance_Ohm * (power_generation - power_consumption_W_))) / diff --git a/src/components/real/power/pcu_initial_study.hpp b/src/components/real/power/pcu_initial_study.hpp index 0f837aa33..ebb338871 100644 --- a/src/components/real/power/pcu_initial_study.hpp +++ b/src/components/real/power/pcu_initial_study.hpp @@ -24,7 +24,8 @@ class PcuInitialStudy : public Component, public ILoggable { * @param [in] battery: Battery * @param [in] component_step_time_s: Component step time [sec] */ - PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, double component_step_time_s); + PcuInitialStudy(const int prescaler, ClockGenerator* clock_generator, const std::vector saps, Battery* battery, + double component_step_time_s); /** * @fn PcuInitialStudy * @brief Constructor @@ -32,7 +33,7 @@ class PcuInitialStudy : public Component, public ILoggable { * @param [in] saps: Solar Array Panels * @param [in] battery: Battery */ - PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery); + PcuInitialStudy(ClockGenerator* clock_generator, const std::vector saps, Battery* battery); /** * @fn ~PcuInitialStudy * @brief Destructor @@ -52,13 +53,13 @@ class PcuInitialStudy : public Component, public ILoggable { std::string GetLogValue() const override; private: - const std::vector saps_; //!< Solar Array Panels - Battery* const battery_; //!< Battery - const double cc_charge_current_C_; //!< Constant charge current [C] - const double cv_charge_voltage_V_; //!< Constant charge voltage [V] - double bus_voltage_V_; //!< Bus voltage [V] - double power_consumption_W_; //!< Power consumption [W] - double compo_step_time_s_; //!< Component step time [sec] + const std::vector saps_; //!< Solar Array Panels + Battery* const battery_; //!< Battery + const double cc_charge_current_C_; //!< Constant charge current [C] + const double cv_charge_voltage_V_; //!< Constant charge voltage [V] + double bus_voltage_V_; //!< Bus voltage [V] + double power_consumption_W_; //!< Power consumption [W] + double compo_step_time_s_; //!< Component step time [sec] // Override functions for Component /** diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index 2050586ba..bd5532de4 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -8,60 +8,62 @@ #include #include -SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double component_step_time_s) +SolarArrayPanel::SolarArrayPanel(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, + double cell_area_m2, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, + const LocalCelestialInformation* local_celestial_information, double component_step_time_s) : Component(prescaler, clock_generator), component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_m2_(cell_area), + cell_area_m2_(cell_area_m2), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_environment_(srp), + srp_environment_(srp_environment), local_celestial_information_(local_celestial_information), compo_step_time_s_(component_step_time_s) { voltage_V_ = 0.0; power_generation_W_ = 0.0; } -SAP::SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - double component_step_time_s) +SolarArrayPanel::SolarArrayPanel(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, + double cell_area_m2, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, double component_step_time_s) : Component(prescaler, clock_generator), component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_m2_(cell_area), + cell_area_m2_(cell_area_m2), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_environment_(srp), + srp_environment_(srp_environment), compo_step_time_s_(component_step_time_s) { voltage_V_ = 0.0; power_generation_W_ = 0.0; } -SAP::SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information) +SolarArrayPanel::SolarArrayPanel(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area_m2, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, + const LocalCelestialInformation* local_celestial_information) : Component(10, clock_generator), component_id_(component_id), number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), - cell_area_m2_(cell_area), + cell_area_m2_(cell_area_m2), normal_vector_(libra::Normalize(normal_vector)), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), - srp_environment_(srp), + srp_environment_(srp_environment), local_celestial_information_(local_celestial_information), compo_step_time_s_(0.1) { voltage_V_ = 0.0; power_generation_W_ = 0.0; } -SAP::SAP(const SAP& obj) +SolarArrayPanel::SolarArrayPanel(const SolarArrayPanel& obj) : Component(obj), component_id_(obj.component_id_), number_of_series_(obj.number_of_series_), @@ -77,26 +79,22 @@ SAP::SAP(const SAP& obj) power_generation_W_ = 0.0; } -SAP::~SAP() {} +SolarArrayPanel::~SolarArrayPanel() {} -double SAP::GetPowerGeneration() const { return power_generation_W_; } - -void SAP::SetVoltage_V(const double voltage) { voltage_V_ = voltage; } - -std::string SAP::GetLogHeader() const { +std::string SolarArrayPanel::GetLogHeader() const { std::string str_tmp = ""; std::string component_name = "sap" + std::to_string(component_id_) + "_"; str_tmp += WriteScalar(component_name + "generated_power", "W"); return str_tmp; } -std::string SAP::GetLogValue() const { +std::string SolarArrayPanel::GetLogValue() const { std::string str_tmp = ""; str_tmp += WriteScalar(power_generation_W_); return str_tmp; } -void SAP::MainRoutine(const int time_count) { +void SolarArrayPanel::MainRoutine(const int time_count) { if (CsvScenarioInterface::IsCsvScenarioEnabled()) { double time_query = compo_step_time_s_ * time_count; const auto solar_constant = srp_environment_->GetSolarConstant_W_m2(); diff --git a/src/components/real/power/solar_array_panel.hpp b/src/components/real/power/solar_array_panel.hpp index 67b4c5972..4a511d627 100644 --- a/src/components/real/power/solar_array_panel.hpp +++ b/src/components/real/power/solar_array_panel.hpp @@ -13,84 +13,86 @@ #include "../../base/component.hpp" -class SAP : public Component, public ILoggable { +class SolarArrayPanel : public Component, public ILoggable { public: /** - * @fn SAP + * @fn SolarArrayPanel * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] component_id: SAP ID + * @param [in] component_id: SolarArrayPanel ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells - * @param [in] cell_area: Area of a solar cell [m2] - * @param [in] normal_vector: Normal vector of SAP on the body fixed frame + * @param [in] cell_area_m2: Area of a solar cell [m2] + * @param [in] normal_vector: Normal vector of SolarArrayPanel on the body fixed frame * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information * @param [in] component_step_time_s: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information, double component_step_time_s); + SolarArrayPanel(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, + double cell_area_m2, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information, + double component_step_time_s); /** - * @fn SAP + * @fn SolarArrayPanel * @brief Constructor with prescaler * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] component_id: SAP ID + * @param [in] component_id: SolarArrayPanel ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells - * @param [in] cell_area: Area of a solar cell [m2] - * @param [in] normal_vector: Normal vector of SAP on the body fixed frame + * @param [in] cell_area_m2: Area of a solar cell [m2] + * @param [in] normal_vector: Normal vector of SolarArrayPanel on the body fixed frame * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] component_step_time_s: Component step time [sec] */ - SAP(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - double component_step_time_s); + SolarArrayPanel(const int prescaler, ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, + double cell_area_m2, libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, double component_step_time_s); /** - * @fn SAP + * @fn SolarArrayPanel * @brief Constructor without prescaler * @note prescaler is set as 10, compo_step_sec is set as * @param [in] clock_generator: Clock generator - * @param [in] component_id: SAP ID + * @param [in] component_id: SolarArrayPanel ID * @param [in] number_of_series: Number of series connected solar cells * @param [in] number_of_parallel: Number of parallel connected solar cells - * @param [in] cell_area: Area of a solar cell [m2] - * @param [in] normal_vector: Normal vector of SAP on the body fixed frame + * @param [in] cell_area_m2: Area of a solar cell [m2] + * @param [in] normal_vector: Normal vector of SolarArrayPanel on the body fixed frame * @param [in] cell_efficiency: Power generation efficiency of solar cell * @param [in] transmission_efficiency: Efficiency of transmission to PCU - * @param [in] srp: Solar Radiation Pressure environment + * @param [in] srp_environment: Solar Radiation Pressure environment * @param [in] local_celestial_information: Local celestial information */ - SAP(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area, - libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, const SolarRadiationPressureEnvironment* srp, - const LocalCelestialInformation* local_celestial_information); + SolarArrayPanel(ClockGenerator* clock_generator, int component_id, int number_of_series, int number_of_parallel, double cell_area_m2, + libra::Vector<3> normal_vector, double cell_efficiency, double transmission_efficiency, + const SolarRadiationPressureEnvironment* srp_environment, const LocalCelestialInformation* local_celestial_information); /** - * @fn SAP + * @fn SolarArrayPanel * @brief Copy constructor */ - SAP(const SAP& obj); + SolarArrayPanel(const SolarArrayPanel& obj); /** - * @fn ~SAP + * @fn ~SolarArrayPanel * @brief Destructor */ - ~SAP(); + ~SolarArrayPanel(); /** - * @fn GetPowerGeneration + * @fn GetPowerGeneration_W * @brief Return power generation [W] */ - double GetPowerGeneration() const; + double GetPowerGeneration_W() const { return power_generation_W_; } + /** * @fn SetVoltage_V * @brief Set voltage */ - void SetVoltage_V(const double voltage); + void SetVoltage_V(const double voltage_V) { voltage_V_ = voltage_V; } // Override ILoggable /** @@ -105,11 +107,11 @@ class SAP : public Component, public ILoggable { std::string GetLogValue() const override; private: - const int component_id_; //!< SAP ID TODO: Use string? + const int component_id_; //!< SolarArrayPanel ID TODO: Use string? const int number_of_series_; //!< Number of series connected solar cells const int number_of_parallel_; //!< Number of parallel connected solar cells const double cell_area_m2_; //!< Solar cell area [m^2] - const libra::Vector<3> normal_vector_; //!< Normal vector of SAP on the body fixed frame + const libra::Vector<3> normal_vector_; //!< Normal vector of SolarArrayPanel on the body fixed frame const double cell_efficiency_; //!< Power generation efficiency of solar cell const double transmission_efficiency_; //!< Efficiency of transmission to PCU diff --git a/src/dynamics/thermal/initialize_node.cpp b/src/dynamics/thermal/initialize_node.cpp index 85530b9ab..e94055594 100644 --- a/src/dynamics/thermal/initialize_node.cpp +++ b/src/dynamics/thermal/initialize_node.cpp @@ -29,7 +29,7 @@ First row is for Header, data begins from the second row Ex. Node_id,Node_label,capacity,solar_radiation,internal_heat,temperature 1,BUS,2.5,0,0,293 -2,SAP,3.2,10,30,288 +2,SolarArrayPanel,3.2,10,30,288 */ Node InitNode(const std::vector& node_str) { From cb63671a1a76666f5dd09584e42675f079219251 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:33:46 +0100 Subject: [PATCH 0863/1086] Fix private function name --- src/components/real/cdh/on_board_computer.cpp | 36 +++++++++---------- src/components/real/cdh/on_board_computer.hpp | 6 ++-- src/simulation/hils/hils_port_manager.cpp | 29 +++++++-------- src/simulation/hils/hils_port_manager.hpp | 4 +-- 4 files changed, 38 insertions(+), 37 deletions(-) diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index c22accdd4..c90193a9a 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -23,73 +23,73 @@ void OBC::Initialize() {} void OBC::MainRoutine(int count) { UNUSED(count); } int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { - if (com_ports_[port_id] != nullptr) { + if (uart_ports_[port_id] != nullptr) { // Port already used return -1; } - com_ports_[port_id] = new UartPort(tx_buffer_size, rx_buffer_size); + uart_ports_[port_id] = new UartPort(tx_buffer_size, rx_buffer_size); return 0; } // Close port and free resources int OBC::CloseComPort(int port_id) { // Port not used - if (com_ports_[port_id] == nullptr) return -1; + if (uart_ports_[port_id] == nullptr) return -1; - UartPort* port = com_ports_.at(port_id); + UartPort* port = uart_ports_.at(port_id); delete port; - com_ports_.erase(port_id); + uart_ports_.erase(port_id); return 0; } int OBC::SendFromObc(int port_id, unsigned char* buffer, int offset, int count) { - UartPort* port = com_ports_[port_id]; + UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->WriteTx(buffer, offset, count); } int OBC::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) { - UartPort* port = com_ports_[port_id]; + UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->ReadTx(buffer, offset, count); } int OBC::SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) { - UartPort* port = com_ports_[port_id]; + UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->WriteRx(buffer, offset, count); } int OBC::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) { - UartPort* port = com_ports_[port_id]; + UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->ReadRx(buffer, offset, count); } int OBC::I2cConnectPort(int port_id, const unsigned char i2c_addr) { - if (i2c_com_ports_[port_id] != nullptr) { + if (i2c_ports_[port_id] != nullptr) { // Port already used } else { - i2c_com_ports_[port_id] = new I2cPort(); + i2c_ports_[port_id] = new I2cPort(); } - i2c_com_ports_[port_id]->RegisterDevice(i2c_addr); + i2c_ports_[port_id]->RegisterDevice(i2c_addr); return 0; } int OBC::I2cCloseComPort(int port_id) { // Port not used - if (i2c_com_ports_[port_id] == nullptr) return -1; + if (i2c_ports_[port_id] == nullptr) return -1; - I2cPort* port = i2c_com_ports_.at(port_id); + I2cPort* port = i2c_ports_.at(port_id); delete port; - i2c_com_ports_.erase(port_id); + i2c_ports_.erase(port_id); return 0; } int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { - I2cPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < len; i++) { i2c_port->WriteRegister(i2c_addr, reg_addr, data[i]); } @@ -97,14 +97,14 @@ int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, co } int OBC::I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, const unsigned char len) { - I2cPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < len; i++) { data[i] = i2c_port->ReadRegister(reg_addr, i2c_addr); } return 0; } int OBC::I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { - I2cPort* i2c_port = i2c_com_ports_[port_id]; + I2cPort* i2c_port = i2c_ports_[port_id]; i2c_port->ReadCommand(i2c_addr, data, len); return 0; } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 6d4d32bef..6b0be2a7d 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -201,9 +201,9 @@ class OBC : public Component { virtual void MainRoutine(int count); private: - std::map com_ports_; //!< UART ports - std::map i2c_com_ports_; //!< I2C ports - std::map gpio_ports_; //!< GPIO ports + std::map uart_ports_; //!< UART ports + std::map i2c_ports_; //!< I2C ports + std::map gpio_ports_; //!< GPIO ports }; #endif // S2E_COMPONENTS_REAL_CDH_OBC_HPP_ diff --git a/src/simulation/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp index 3b641709b..7978efc96 100644 --- a/src/simulation/hils/hils_port_manager.cpp +++ b/src/simulation/hils/hils_port_manager.cpp @@ -109,12 +109,12 @@ int HilsPortManager::UartSend(unsigned int port_id, const unsigned char* buffer, // I2C Target Communication port functions int HilsPortManager::I2cTargetConnectComPort(unsigned int port_id) { #ifdef USE_HILS - if (i2c_com_ports_[port_id] != nullptr) { + if (i2c_ports_[port_id] != nullptr) { printf("Error: Port is already used\n"); return -1; } - i2c_com_ports_[port_id] = new HilsI2cTargetPort(port_id); - i2c_com_ports_[port_id]->RegisterDevice(); + i2c_ports_[port_id] = new HilsI2cTargetPort(port_id); + i2c_ports_[port_id]->RegisterDevice(); return 0; #else UNUSED(port_id); @@ -125,14 +125,14 @@ int HilsPortManager::I2cTargetConnectComPort(unsigned int port_id) { int HilsPortManager::I2cTargetCloseComPort(unsigned int port_id) { #ifdef USE_HILS - if (i2c_com_ports_[port_id] == nullptr) { + if (i2c_ports_[port_id] == nullptr) { // Port not used return -1; } - i2c_com_ports_[port_id]->ClosePort(); - HilsI2cTargetPort* port = i2c_com_ports_.at(port_id); + i2c_ports_[port_id]->ClosePort(); + HilsI2cTargetPort* port = i2c_ports_.at(port_id); delete port; - i2c_com_ports_.erase(port_id); + i2c_ports_.erase(port_id); return 0; #else UNUSED(port_id); @@ -143,7 +143,7 @@ int HilsPortManager::I2cTargetCloseComPort(unsigned int port_id) { int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < len; i++) { port->WriteRegister(reg_addr + i, data[i]); @@ -161,7 +161,7 @@ int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_addr, unsigned char* data, const unsigned char len) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < len; i++) { data[i] = port->ReadRegister(reg_addr + i); @@ -179,7 +179,7 @@ int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned int HilsPortManager::I2cTargetReadCommand(unsigned int port_id, unsigned char* data, const unsigned char len) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; port->ReadCommand(data, len); return 0; @@ -194,7 +194,7 @@ int HilsPortManager::I2cTargetReadCommand(unsigned int port_id, unsigned char* d int HilsPortManager::I2cTargetReceive(unsigned int port_id) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; int ret = port->Receive(); #ifdef HILS_PORT_MANAGER_SHOW_DEBUG_DATA @@ -212,7 +212,7 @@ int HilsPortManager::I2cTargetReceive(unsigned int port_id) { int HilsPortManager::I2cTargetSend(unsigned int port_id, const unsigned char len) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; int ret = port->Send(len); #ifdef HILS_PORT_MANAGER_SHOW_DEBUG_DATA @@ -231,7 +231,7 @@ int HilsPortManager::I2cTargetSend(unsigned int port_id, const unsigned char len int HilsPortManager::I2cTargetGetStoredFrameCounter(unsigned int port_id) { #ifdef USE_HILS - HilsI2cTargetPort* port = i2c_com_ports_[port_id]; + HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; return port->GetStoredFrameCounter(); #else @@ -242,7 +242,8 @@ int HilsPortManager::I2cTargetGetStoredFrameCounter(unsigned int port_id) { } // I2C Controller Communication port functions -int HilsPortManager::I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size) { +int HilsPortManager::I2cControllerConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, + unsigned int rx_buffer_size) { return UartConnectComPort(port_id, baud_rate, tx_buffer_size, rx_buffer_size); } diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index f48492982..781dd9b38 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -162,8 +162,8 @@ class HilsPortManager { private: #ifdef USE_HILS - std::map uart_com_ports_; //!< UART ports - std::map i2c_com_ports_; //!< I2C ports + std::map uart_com_ports_; //!< UART ports + std::map i2c_ports_; //!< I2C ports #endif }; From 7d55ec7de560bdc800c9028352cf6c95cf284ca5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:36:43 +0100 Subject: [PATCH 0864/1086] Fix function argument names --- src/components/real/cdh/on_board_computer.cpp | 46 +++++----- src/components/real/cdh/on_board_computer.hpp | 53 +++++------ .../real/cdh/on_board_computer_with_c2a.cpp | 92 +++++++++---------- .../real/cdh/on_board_computer_with_c2a.hpp | 84 ++++++++--------- src/simulation/hils/hils_port_manager.cpp | 37 ++++---- src/simulation/hils/hils_port_manager.hpp | 20 ++-- 6 files changed, 167 insertions(+), 165 deletions(-) diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index c90193a9a..88e04c42c 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -9,10 +9,10 @@ OBC::OBC(ClockGenerator* clock_generator) : Component(1, clock_generator) { Init OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port) : Component(prescaler, clock_generator, power_port) { Initialize(); } OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, - const double assumed_power_consumption) + const double assumed_power_consumption_W) : Component(prescaler, clock_generator, power_port) { power_port_->SetMinimumVoltage_V(minimum_voltage_V); - power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption); + power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption_W); Initialize(); } @@ -20,7 +20,7 @@ OBC::~OBC() {} void OBC::Initialize() {} -void OBC::MainRoutine(int count) { UNUSED(count); } +void OBC::MainRoutine(const int time_count) { UNUSED(time_count); } int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { if (uart_ports_[port_id] != nullptr) { @@ -42,37 +42,37 @@ int OBC::CloseComPort(int port_id) { return 0; } -int OBC::SendFromObc(int port_id, unsigned char* buffer, int offset, int count) { +int OBC::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - return port->WriteTx(buffer, offset, count); + return port->WriteTx(buffer, offset, length); } -int OBC::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) { +int OBC::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - return port->ReadTx(buffer, offset, count); + return port->ReadTx(buffer, offset, length); } -int OBC::SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) { +int OBC::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - return port->WriteRx(buffer, offset, count); + return port->WriteRx(buffer, offset, length); } -int OBC::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) { +int OBC::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - return port->ReadRx(buffer, offset, count); + return port->ReadRx(buffer, offset, length); } -int OBC::I2cConnectPort(int port_id, const unsigned char i2c_addr) { +int OBC::I2cConnectPort(int port_id, const unsigned char i2c_address) { if (i2c_ports_[port_id] != nullptr) { // Port already used } else { i2c_ports_[port_id] = new I2cPort(); } - i2c_ports_[port_id]->RegisterDevice(i2c_addr); + i2c_ports_[port_id]->RegisterDevice(i2c_address); return 0; } @@ -87,25 +87,25 @@ int OBC::I2cCloseComPort(int port_id) { return 0; } -int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, - const unsigned char len) { +int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; - for (int i = 0; i < len; i++) { - i2c_port->WriteRegister(i2c_addr, reg_addr, data[i]); + for (int i = 0; i < length; i++) { + i2c_port->WriteRegister(i2c_address, reg_address, data[i]); } return 0; } -int OBC::I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, - const unsigned char len) { +int OBC::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; - for (int i = 0; i < len; i++) { - data[i] = i2c_port->ReadRegister(reg_addr, i2c_addr); + for (int i = 0; i < length; i++) { + data[i] = i2c_port->ReadRegister(reg_address, i2c_address); } return 0; } -int OBC::I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { +int OBC::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; - i2c_port->ReadCommand(i2c_addr, data, len); + i2c_port->ReadCommand(i2c_address, data, length); return 0; } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 6b0be2a7d..a12c232cc 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -41,9 +41,10 @@ class OBC : public Component { * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port * @param [in] minimum_voltage_V: Minimum voltage [V] - * @param [in] assumed_power_consumption: Assumed power consumption [W] + * @param [in] assumed_power_consumption_W: Assumed power consumption [W] */ - OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, const double assumed_power_consumption); + OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, + const double assumed_power_consumption_W); /** * @fn ~OBC * @brief Destructor @@ -73,20 +74,20 @@ class OBC : public Component { * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of send data + * @param [in] length: Length of send data * @return Number of written byte */ - virtual int SendFromObc(int port_id, unsigned char* buffer, int offset, int count); + virtual int SendFromObc(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByCompo * @brief Read data from OBC to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of read data + * @param [in] length: Length of read data * @return Number of read byte */ - virtual int ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count); + virtual int ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length); /** * @fn SendFromComponent @@ -94,20 +95,20 @@ class OBC : public Component { * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of send data + * @param [in] length: Length of send data * @return Number of written byte */ - virtual int SendFromCompo(int port_id, unsigned char* buffer, int offset, int count); + virtual int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc * @brief Read data from component to OBC with UART used by OBC side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of read data + * @param [in] length: Length of read data * @return Number of read byte */ - virtual int ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count); + virtual int ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length); // I2C Communication port functions /** @@ -115,10 +116,10 @@ class OBC : public Component { * @brief Connect I2C communication port between OBC (I2C controller) and a component (I2C target) * @note Multiple target can be connected to one port ID * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of target device + * @param [in] i2c_address: I2C address of target device * @return 0 */ - virtual int I2cConnectPort(int port_id, const unsigned char i2c_addr); + virtual int I2cConnectPort(int port_id, const unsigned char i2c_address); /** * @fn I2cCloseComPort * @brief Close I2C communication port between OBC and a component @@ -130,36 +131,36 @@ class OBC : public Component { * @fn I2cComponentWriteRegister * @brief Write value in the target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] i2c_address: I2C address of the target device + * @param [in] reg_address: Register address of the target device * @param [in] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - virtual int I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, - const unsigned char len); + virtual int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + const unsigned char length); /** * @fn I2cComponentReadRegister * @brief Read value in the target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] i2c_address: I2C address of the target device + * @param [in] reg_address: Register address of the target device * @param [out] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - virtual int I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, - const unsigned char len); + virtual int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length); /** * @fn I2cComponentReadCommand * @brief Read command from OBC to target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - virtual int I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len); + virtual int I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length); // GPIO port functions /** @@ -198,7 +199,7 @@ class OBC : public Component { * @brief Main routine to execute flight software * @note Users need to write flight software */ - virtual void MainRoutine(int count); + virtual void MainRoutine(int time_count); private: std::map uart_ports_; //!< UART ports diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index bb00e729a..c78443d73 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -44,8 +44,8 @@ void OBC_C2A::Initialize() { #endif } -void OBC_C2A::MainRoutine(int count) { - UNUSED(count); +void OBC_C2A::MainRoutine(const int time_count) { + UNUSED(time_count); #ifdef USE_C2A if (is_initialized == false) { @@ -81,54 +81,54 @@ int OBC_C2A::CloseComPort(int port_id) { return 0; } -int OBC_C2A::SendFromObc(int port_id, unsigned char* buffer, int offset, int count) { - return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, count); +int OBC_C2A::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { + return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, length); } -int OBC_C2A::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) { +int OBC_C2A::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; - return port->ReadTx(buffer, offset, count); + return port->ReadTx(buffer, offset, length); } -int OBC_C2A::SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) { +int OBC_C2A::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; - return port->WriteRx(buffer, offset, count); + return port->WriteRx(buffer, offset, length); } -int OBC_C2A::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) { - return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, count); +int OBC_C2A::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { + return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, length); } // Static functions -int OBC_C2A::SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int count) { +int OBC_C2A::SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; - return port->WriteTx(buffer, offset, count); + return port->WriteTx(buffer, offset, length); } -int OBC_C2A::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int count) { +int OBC_C2A::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; - return port->ReadRx(buffer, offset, count); + return port->ReadRx(buffer, offset, length); } // If the character encoding of C2A is UTF-8, these functions are not necessary, // and users can directory use SendFromObc_C2A and ReceivedByObc_C2A -int OBC_C2A_SendFromObc(int port_id, unsigned char* buffer, int offset, int count) { - return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, count); +int OBC_C2A_SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { + return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, length); } -int OBC_C2A_ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) { - return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, count); +int OBC_C2A_ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { + return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, length); } -int OBC_C2A::I2cConnectPort(int port_id, const unsigned char i2c_addr) { +int OBC_C2A::I2cConnectPort(int port_id, const unsigned char i2c_address) { if (i2c_com_ports_c2a_[port_id] != nullptr) { // Port already used } else { i2c_com_ports_c2a_[port_id] = new I2cPort(); } - i2c_com_ports_c2a_[port_id]->RegisterDevice(i2c_addr); + i2c_com_ports_c2a_[port_id]->RegisterDevice(i2c_address); return 0; } @@ -143,63 +143,63 @@ int OBC_C2A::I2cCloseComPort(int port_id) { return 0; } -int OBC_C2A::I2cWriteCommand(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { +int OBC_C2A::I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - i2c_port->WriteCommand(i2c_addr, data, len); + i2c_port->WriteCommand(i2c_address, data, length); return 0; } -int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { +int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - if (len == 1) { - i2c_port->WriteRegister(i2c_addr, data[0]); + if (length == 1) { + i2c_port->WriteRegister(i2c_address, data[0]); } else { - for (unsigned char i = 0; i < len - 1; i++) { - i2c_port->WriteRegister(i2c_addr, data[0] + i, data[i + 1]); + for (unsigned char i = 0; i < length - 1; i++) { + i2c_port->WriteRegister(i2c_address, data[0] + i, data[i + 1]); } } return 0; } -int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { +int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - for (int i = 0; i < len; i++) { - data[i] = i2c_port->ReadRegister(i2c_addr); + for (int i = 0; i < length; i++) { + data[i] = i2c_port->ReadRegister(i2c_address); } return 0; } -int OBC_C2A::I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, - const unsigned char len) { +int OBC_C2A::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - for (unsigned char i = 0; i < len; i++) { - i2c_port->WriteRegister(i2c_addr, reg_addr + i, data[i]); + for (unsigned char i = 0; i < length; i++) { + i2c_port->WriteRegister(i2c_address, reg_address + i, data[i]); } return 0; } -int OBC_C2A::I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, - const unsigned char len) { +int OBC_C2A::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - for (unsigned char i = 0; i < len; i++) { - data[i] = i2c_port->ReadRegister(i2c_addr, reg_addr + i); + for (unsigned char i = 0; i < length; i++) { + data[i] = i2c_port->ReadRegister(i2c_address, reg_address + i); } return 0; } -int OBC_C2A::I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { +int OBC_C2A::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; - i2c_port->ReadCommand(i2c_addr, data, len); + i2c_port->ReadCommand(i2c_address, data, length); return 0; } -int OBC_C2A_I2cWriteCommand(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { - return OBC_C2A::I2cWriteCommand(port_id, i2c_addr, data, len); +int OBC_C2A_I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { + return OBC_C2A::I2cWriteCommand(port_id, i2c_address, data, length); } -int OBC_C2A_I2cWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len) { - return OBC_C2A::I2cWriteRegister(port_id, i2c_addr, data, len); +int OBC_C2A_I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { + return OBC_C2A::I2cWriteRegister(port_id, i2c_address, data, length); } -int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) { - return OBC_C2A::I2cReadRegister(port_id, i2c_addr, data, len); +int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { + return OBC_C2A::I2cReadRegister(port_id, i2c_address, data, length); } int OBC_C2A::GpioConnectPort(int port_id) { diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index dd3164f39..8fb651bb4 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -67,20 +67,20 @@ class OBC_C2A : public OBC { * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of send data + * @param [in] length: Length of send data * @return Number of written byte */ - int SendFromObc(int port_id, unsigned char* buffer, int offset, int count) override; + int SendFromObc(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByCompo * @brief Read data from OBC to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of read data + * @param [in] length: Length of read data * @return Number of read byte */ - int ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int count) override; + int ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn SendFromComponent @@ -88,20 +88,20 @@ class OBC_C2A : public OBC { * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of send data + * @param [in] length: Length of send data * @return Number of written byte */ - int SendFromCompo(int port_id, unsigned char* buffer, int offset, int count) override; + int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByObc * @brief Read data from component to OBC with UART used by OBC side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of read data + * @param [in] length: Length of read data * @return Number of read byte */ - int ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count) override; + int ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) override; // Static function for C2A /** @@ -110,20 +110,20 @@ class OBC_C2A : public OBC { * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of send data + * @param [in] length: Length of send data * @return Number of written byte */ - static int SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int count); + static int SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc_C2A * @brief Read data from component to OBC with UART used by C2A flight software * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer - * @param [in] count: Length of read data + * @param [in] length: Length of read data * @return Number of read byte */ - static int ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int count); + static int ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int length); // I2C /** @@ -131,11 +131,11 @@ class OBC_C2A : public OBC { * @brief Connect I2C communication port between OBC (I2C controller) and a component (I2C target) * @note Multiple target can be connected to one port ID * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of target device + * @param [in] i2c_address: I2C address of target device * @return 0 */ - int I2cConnectPort(int port_id, const unsigned char i2c_addr) override; + int I2cConnectPort(int port_id, const unsigned char i2c_address) override; /** * @fn I2cCloseComPort * @brief Close I2C communication port between OBC and a component @@ -147,68 +147,68 @@ class OBC_C2A : public OBC { * @fn I2cComponentWriteRegister * @brief Write value in the target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] i2c_address: I2C address of the target device + * @param [in] reg_address: Register address of the target device * @param [in] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - int I2cComponentWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, const unsigned char* data, - const unsigned char len) override; + int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + const unsigned char length) override; /** * @fn I2cComponentReadRegister * @brief Read value in the target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device - * @param [in] reg_addr: Register address of the target device + * @param [in] i2c_address: I2C address of the target device + * @param [in] reg_address: Register address of the target device * @param [out] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - int I2cComponentReadRegister(int port_id, const unsigned char i2c_addr, const unsigned char reg_addr, unsigned char* data, - const unsigned char len) override; + int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length) override; /** * @fn I2cComponentReadCommand * @brief Read command from OBC to target device's register * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - int I2cComponentReadCommand(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len) override; + int I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) override; // Static function for C2A /** * @fn I2cWriteCommand * @brief Write command to target device used in C2A flight software * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - static int I2cWriteCommand(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len); + static int I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length); /** * @fn I2cWriteRegister * @brief Write value in the target device's register used in C2A flight software * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [in] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - static int I2cWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len); + static int I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length); /** * @fn I2cComponentReadRegister * @brief Read value in the target device's register used in C2A flight software * @param [in] port_id: Port ID - * @param [in] i2c_addr: I2C address of the target device + * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer - * @param [in] len: Length of data + * @param [in] length: Length of data * @return 0 */ - static int I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len); + static int I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length); // GPIO /** @@ -258,7 +258,7 @@ class OBC_C2A : public OBC { * @fn MainRoutine * @brief Main routine to execute C2A */ - void MainRoutine(int count); + void MainRoutine(const int time_count); /** * @fn Initialize * @brief Initialize function @@ -275,13 +275,13 @@ class OBC_C2A : public OBC { // TODO: Delete these functions since C2A is changed to use UTF-8 // C2A communication functions -int OBC_C2A_SendFromObc(int port_id, unsigned char* buffer, int offset, int count); -int OBC_C2A_ReceivedByObc(int port_id, unsigned char* buffer, int offset, int count); +int OBC_C2A_SendFromObc(int port_id, unsigned char* buffer, int offset, int length); +int OBC_C2A_ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length); // I2C -int OBC_C2A_I2cWriteCommand(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len); -int OBC_C2A_I2cWriteRegister(int port_id, const unsigned char i2c_addr, const unsigned char* data, const unsigned char len); -int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_addr, unsigned char* data, const unsigned char len); +int OBC_C2A_I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length); +int OBC_C2A_I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length); +int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length); // GPIO int OBC_C2A_GpioWrite(int port_id, const bool is_high); diff --git a/src/simulation/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp index 7978efc96..a70902bcb 100644 --- a/src/simulation/hils/hils_port_manager.cpp +++ b/src/simulation/hils/hils_port_manager.cpp @@ -141,52 +141,53 @@ int HilsPortManager::I2cTargetCloseComPort(unsigned int port_id) { #endif } -int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_addr, const unsigned char* data, const unsigned char len) { +int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, + const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; - for (unsigned char i = 0; i < len; i++) { - port->WriteRegister(reg_addr + i, data[i]); + for (unsigned char i = 0; i < length; i++) { + port->WriteRegister(reg_address + i, data[i]); } return 0; #else UNUSED(port_id); - UNUSED(reg_addr); + UNUSED(reg_address); UNUSED(data); - UNUSED(len); + UNUSED(length); return -1; #endif } -int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_addr, unsigned char* data, const unsigned char len) { +int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; - for (unsigned char i = 0; i < len; i++) { - data[i] = port->ReadRegister(reg_addr + i); + for (unsigned char i = 0; i < length; i++) { + data[i] = port->ReadRegister(reg_address + i); } return 0; #else UNUSED(port_id); - UNUSED(reg_addr); + UNUSED(reg_address); UNUSED(data); - UNUSED(len); + UNUSED(length); return -1; #endif } -int HilsPortManager::I2cTargetReadCommand(unsigned int port_id, unsigned char* data, const unsigned char len) { +int HilsPortManager::I2cTargetReadCommand(unsigned int port_id, unsigned char* data, const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; - port->ReadCommand(data, len); + port->ReadCommand(data, length); return 0; #else UNUSED(port_id); UNUSED(data); - UNUSED(len); + UNUSED(length); return -1; #endif @@ -210,20 +211,20 @@ int HilsPortManager::I2cTargetReceive(unsigned int port_id) { #endif } -int HilsPortManager::I2cTargetSend(unsigned int port_id, const unsigned char len) { +int HilsPortManager::I2cTargetSend(unsigned int port_id, const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; - int ret = port->Send(len); + int ret = port->Send(length); #ifdef HILS_PORT_MANAGER_SHOW_DEBUG_DATA - if (len > 0) { - printf("I2C PORT ID: %d sent %d bytes\n", port_id, len); + if (length > 0) { + printf("I2C PORT ID: %d sent %d bytes\n", port_id, length); } #endif return ret; #else UNUSED(port_id); - UNUSED(len); + UNUSED(length); return -1; #endif diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index 781dd9b38..e0dbe6839 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -81,28 +81,28 @@ class HilsPortManager { * @fn I2cTargetReadRegister * @brief Read I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_addr: Register address to read + * @param [in] reg_address: Register address to read * @param [out] data: Data buffer to store the read data - * @param [in] len: Read data length + * @param [in] length: Read data length */ - virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_addr, unsigned char* data, const unsigned char len); + virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length); /** * @fn I2cTargetWriteRegister * @brief Write data to I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_addr: Register address to write + * @param [in] reg_address: Register address to write * @param [in] data: Data to write - * @param [in] len: Write data length + * @param [in] length: Write data length */ - virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_addr, const unsigned char* data, const unsigned char len); + virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, const unsigned char length); /** * @fn I2cTargetReadCommand * @brief Read I2C command buffer in S2E * @param [in] port_id: COM port ID * @param [out] data: Data buffer to store the read data - * @param [in] len: Read data length + * @param [in] length: Read data length */ - virtual int I2cTargetReadCommand(unsigned int port_id, unsigned char* data, const unsigned char len); + virtual int I2cTargetReadCommand(unsigned int port_id, unsigned char* data, const unsigned char length); /** * @fn I2cTargetReceive @@ -114,9 +114,9 @@ class HilsPortManager { * @fn I2cTargetSend * @brief Send data to the I2C-USB converter * @param [in] port_id: COM port ID - * @param [in] len: Data length to write + * @param [in] length: Data length to write */ - virtual int I2cTargetSend(unsigned int port_id, const unsigned char len); + virtual int I2cTargetSend(unsigned int port_id, const unsigned char length); /** * @fn I2cTargetGetStoredFrameCounter * @brief Get stored frame counter From 467d1d9cef68a9237fc277047d29797902e8a405 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:39:06 +0100 Subject: [PATCH 0865/1086] Rename OBC to OnBoardComputer --- .../base/gpio_connection_with_obc.cpp | 4 +- .../base/gpio_connection_with_obc.hpp | 16 +++--- src/components/base/i2c_controller.hpp | 2 +- .../i2c_target_communication_with_obc.cpp | 6 +-- .../i2c_target_communication_with_obc.hpp | 20 ++++---- .../base/uart_communication_with_obc.cpp | 8 +-- .../base/uart_communication_with_obc.hpp | 40 +++++++-------- .../examples/example_i2c_target_for_hils.cpp | 2 +- .../examples/example_i2c_target_for_hils.hpp | 6 +-- .../example_serial_communication_for_hils.cpp | 2 +- .../example_serial_communication_for_hils.hpp | 10 ++-- .../example_serial_communication_with_obc.cpp | 6 +-- .../example_serial_communication_with_obc.hpp | 20 ++++---- src/components/ports/hils_i2c_target_port.hpp | 2 +- src/components/ports/i2c_port.hpp | 12 ++--- src/components/ports/uart_port.hpp | 14 +++--- src/components/real/cdh/on_board_computer.cpp | 49 ++++++++++--------- src/components/real/cdh/on_board_computer.hpp | 48 +++++++++--------- .../real/cdh/on_board_computer_with_c2a.cpp | 6 +-- .../real/cdh/on_board_computer_with_c2a.hpp | 30 ++++++------ src/simulation/hils/hils_port_manager.hpp | 4 +- .../sample_spacecraft/sample_components.cpp | 4 +- .../sample_spacecraft/sample_components.hpp | 4 +- 23 files changed, 159 insertions(+), 156 deletions(-) diff --git a/src/components/base/gpio_connection_with_obc.cpp b/src/components/base/gpio_connection_with_obc.cpp index 7e9f8a6b5..3ef349ad1 100644 --- a/src/components/base/gpio_connection_with_obc.cpp +++ b/src/components/base/gpio_connection_with_obc.cpp @@ -1,12 +1,12 @@ /** * @file gpio_connection_with_obc.cpp - * @brief Base class for GPIO communication with OBC flight software + * @brief Base class for GPIO communication with OnBoardComputer flight software * TODO: consider relation with IGPIOCompo */ #include "gpio_connection_with_obc.hpp" -GpioConnectionWithObc::GpioConnectionWithObc(const std::vector port_id, OBC* obc) : port_id_(port_id), obc_(obc) { +GpioConnectionWithObc::GpioConnectionWithObc(const std::vector port_id, OnBoardComputer* obc) : port_id_(port_id), obc_(obc) { for (size_t i = 0; i < port_id_.size(); i++) { obc_->GpioConnectPort(port_id_[i]); } diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index a520c7bf4..43c47a376 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file gpio_connection_with_obc.hpp - * @brief Base class for GPIO communication with OBC flight software + * @brief Base class for GPIO communication with OnBoardComputer flight software * TODO: consider relation with IGPIOCompo */ @@ -11,8 +11,8 @@ /** * @class GpioConnectionWithObc - * @brief Base class for GPIO communication with OBC flight software - * @note Components which want to communicate with OBC using GPIO have to inherit this. + * @brief Base class for GPIO communication with OnBoardComputer flight software + * @note Components which want to communicate with OnBoardComputer using GPIO have to inherit this. */ class GpioConnectionWithObc { public: @@ -20,9 +20,9 @@ class GpioConnectionWithObc { * @fn GpioConnectionWithObc * @brief Constructor for SILS mode * @param [in] port_id: Port ID GPIO line - * @param [in] obc: The communication target OBC + * @param [in] obc: The communication target OnBoardComputer */ - GpioConnectionWithObc(const std::vector port_id, OBC* obc); + GpioConnectionWithObc(const std::vector port_id, OnBoardComputer* obc); /** * @fn ~GpioConnectionWithObc * @brief Destructor @@ -33,21 +33,21 @@ class GpioConnectionWithObc { /** * @fn Read * @brief Read the GPIO state - * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OnBoardComputer. * @return High(True) or Low(False) of GPIO state */ bool Read(const int index); /** * @fn Write * @brief Write the GPIO state - * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OnBoardComputer. * @param [in] is_high: High(True) or Low(False) of GPIO state */ void Write(const int index, const bool is_high); private: std::vector port_id_; //!< Port ID GPIO line - OBC* obc_; //!< The communication target OBC + OnBoardComputer* obc_; //!< The communication target OnBoardComputer }; #endif // S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 7475b91db..4b1ed1d64 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -12,7 +12,7 @@ /** * @class I2cController * @brief This class simulates the I2C Controller communication with the I2C Target. - * @note Generally, I2C controller side is OBC, and components are target side. + * @note Generally, I2C controller side is OnBoardComputer, and components are target side. * The main purpose is to validate the emulated I2C Target component in the HILS test. * This class works only HILS mode */ diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index 63a92f096..ea5cf34e6 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -1,12 +1,12 @@ /** * @file i2c_target_communication_with_obc.cpp - * @brief Base class for I2C communication as target side with OBC flight software + * @brief Base class for I2C communication as target side with OnBoardComputer flight software */ #include "i2c_target_communication_with_obc.hpp" #include -I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc) +I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OnBoardComputer* obc) : sils_port_id_(sils_port_id), i2c_address_(i2c_address), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; @@ -33,7 +33,7 @@ I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int } I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, - const unsigned char i2c_address, OBC* obc, HilsPortManager* hils_port_manager) + const unsigned char i2c_address, OnBoardComputer* obc, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), i2c_address_(i2c_address), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::HILS; diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 32041489f..9297fed45 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file i2c_target_communication_with_obc.hpp - * @brief Base class for I2C communication as target side with OBC flight software + * @brief Base class for I2C communication as target side with OnBoardComputer flight software */ #ifndef S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ @@ -12,19 +12,19 @@ /** * @class I2cTargetCommunicationWithObc - * @brief Base class for I2C communication as target side with OBC flight software - * @note Generally, components are the target side of I2C (OBC is the controller side). + * @brief Base class for I2C communication as target side with OnBoardComputer flight software + * @note Generally, components are the target side of I2C (OnBoardComputer is the controller side). */ class I2cTargetCommunicationWithObc { public: /** * @fn I2cTargetCommunicationWithObc * @brief Constructor for SILS mode - * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode * @param [in] i2c_address: I2C address for the target - * @param [in] obc: The communication target OBC + * @param [in] obc: The communication target OnBoardComputer */ - I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OBC* obc); + I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OnBoardComputer* obc); /** * @fn I2cTargetCommunicationWithObc * @brief Constructor for HILS mode @@ -36,13 +36,13 @@ class I2cTargetCommunicationWithObc { /** * @fn I2cTargetCommunicationWithObc * @brief Constructor for both SILS and HILS mode - * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] i2c_address: I2C address for the target - * @param [in] obc: The communication target OBC + * @param [in] obc: The communication target OnBoardComputer * @param [in] hils_port_manager: HILS port manager */ - I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OBC* obc, + I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OnBoardComputer* obc, HilsPortManager* hils_port_manager); /** * @fn I2cTargetCommunicationWithObc @@ -117,7 +117,7 @@ class I2cTargetCommunicationWithObc { OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OBC* obc_; //!< Communication target OBC + OnBoardComputer* obc_; //!< Communication target OnBoardComputer HilsPortManager* hils_port_manager_; //!< HILS port manager }; diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index ffbdafd4c..373da17e4 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -1,13 +1,13 @@ /** * @file uart_communication_with_obc.cpp - * @brief Base class for serial communication (e.g., UART) with OBC flight software + * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software */ #include "uart_communication_with_obc.hpp" #include -UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, OBC* obc) : sils_port_id_(sils_port_id), obc_(obc) { +UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, OnBoardComputer* obc) : sils_port_id_(sils_port_id), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; printf("Error: USE_HILS:ON Check compo initialization\n"); @@ -20,7 +20,7 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_ } UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, - const unsigned int rx_buffer_size, OBC* obc) + const unsigned int rx_buffer_size, OnBoardComputer* obc) : sils_port_id_(sils_port_id), tx_buffer_size_(tx_buffer_size), rx_buffer_size_(rx_buffer_size), obc_(obc) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; @@ -64,7 +64,7 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_ InitializeObcComBase(); } -UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, +UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), baud_rate_(baud_rate), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 0f7a1c3dc..09249e2bb 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file uart_communication_with_obc.hpp - * @brief Base class for serial communication (e.g., UART) with OBC flight software + * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software */ #ifndef S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ @@ -13,7 +13,7 @@ /** * @enum OBC_COM_UART_MODE * @brief Simulation mode (SILS or HILS) - * @details In the SILS mode, S2E does not need to communicate with OBC in S2E + * @details In the SILS mode, S2E does not need to communicate with OnBoardComputer in S2E */ enum class OBC_COM_UART_MODE { SILS, //!< Software In the Loop Simulation @@ -23,8 +23,8 @@ enum class OBC_COM_UART_MODE { /** * @class UartCommunicationWithObc - * @brief Base class for serial communication (e.g., UART) with OBC flight software - * @note Components which want to communicate with OBC using serial communication have to inherit this. + * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software + * @note Components which want to communicate with OnBoardComputer using serial communication have to inherit this. */ class UartCommunicationWithObc { public: @@ -32,19 +32,19 @@ class UartCommunicationWithObc { * @fn UartCommunicationWithObc * @brief Constructor for SILS mode * @note Default buffer size is used - * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode - * @param [in] obc: The communication target OBC + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode + * @param [in] obc: The communication target OnBoardComputer */ - UartCommunicationWithObc(const unsigned int sils_port_id, OBC* obc); + UartCommunicationWithObc(const unsigned int sils_port_id, OnBoardComputer* obc); /** * @fn UartCommunicationWithObc * @brief Constructor for SILS mode - * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode - * @param [in] tx_buffer_size: TX (Component to OBC) buffer size - * @param [in] rx_buffer_size: RX (OBC to Component) buffer size - * @param [in] obc: The communication target OBC + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode + * @param [in] tx_buffer_size: TX (Component to OnBoardComputer) buffer size + * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size + * @param [in] obc: The communication target OnBoardComputer */ - UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OBC* obc); + UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OnBoardComputer* obc); /** * @fn UartCommunicationWithObc * @brief Constructor for HILS mode @@ -59,8 +59,8 @@ class UartCommunicationWithObc { * @brief Constructor for HILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port - * @param [in] tx_buffer_size: TX (Component to OBC) buffer size - * @param [in] rx_buffer_size: RX (OBC to Component) buffer size + * @param [in] tx_buffer_size: TX (Component to OnBoardComputer) buffer size + * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size * @param [in] hils_port_manager: HILS port manager */ UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, @@ -69,13 +69,13 @@ class UartCommunicationWithObc { * @fn UartCommunicationWithObc * @brief Constructor for both SILS and HILS mode * @note Default buffer size is used - * @param [in] sils_port_id: Port ID for communication line b/w OBC in the SILS mode - * @param [in] obc: The communication target OBC + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode + * @param [in] obc: The communication target OnBoardComputer * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - UartCommunicationWithObc(const int sils_port_id, OBC* obc, const unsigned int hils_port_id, const unsigned int baud_rate, + UartCommunicationWithObc(const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager); /** * @fn ~UartCommunicationWithObc @@ -100,13 +100,13 @@ class UartCommunicationWithObc { unsigned int sils_port_id_; //!< Port ID for SILS unsigned int hils_port_id_; //!< Port ID for HILS unsigned int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 - unsigned int tx_buffer_size_; //!< TX (Component to OBC) buffer size - unsigned int rx_buffer_size_; //!< RX (OBC to Component) buffer size + unsigned int tx_buffer_size_; //!< TX (Component to OnBoardComputer) buffer size + unsigned int rx_buffer_size_; //!< RX (OnBoardComputer to Component) buffer size bool is_connected_ = false; //!< Connection flag OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OBC* obc_; //!< Communication target OBC + OnBoardComputer* obc_; //!< Communication target OnBoardComputer HilsPortManager* hils_port_manager_; //!< HILS port manager /** diff --git a/src/components/examples/example_i2c_target_for_hils.cpp b/src/components/examples/example_i2c_target_for_hils.cpp index 49733b0be..3ec63ed3e 100644 --- a/src/components/examples/example_i2c_target_for_hils.cpp +++ b/src/components/examples/example_i2c_target_for_hils.cpp @@ -6,7 +6,7 @@ #include "example_i2c_target_for_hils.hpp" ExampleI2cTargetForHils::ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, - unsigned char i2c_address, OBC* obc, const unsigned int hils_port_id, + unsigned char i2c_address, OnBoardComputer* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager) : Component(prescaler, clock_generator), I2cTargetCommunicationWithObc(sils_port_id, hils_port_id, i2c_address, obc, hils_port_manager) {} diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 8f50b5984..da182c7af 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -26,13 +26,13 @@ class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationW * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator - * @param [in] sils_port_id: Port ID for communication line b/w OBC + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer * @param [in] i2c_address: I2C address of the target device (This value should be compatible with MFT200XD's setting) - * @param [in] obc: The communication target OBC + * @param [in] obc: The communication target OnBoardComputer * @param [in] hils_port_id: ID of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, unsigned char i2c_address, OBC* obc, + ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, unsigned char i2c_address, OnBoardComputer* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cTargetForHils diff --git a/src/components/examples/example_serial_communication_for_hils.cpp b/src/components/examples/example_serial_communication_for_hils.cpp index f6a312435..8986e85db 100644 --- a/src/components/examples/example_serial_communication_for_hils.cpp +++ b/src/components/examples/example_serial_communication_for_hils.cpp @@ -6,7 +6,7 @@ #include -ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OBC* obc, +ExampleSerialCommunicationForHils::ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id) : Component(300, clock_generator), UartCommunicationWithObc(sils_port_id, obc, hils_port_id, baud_rate, hils_port_manager), mode_id_(mode_id) {} diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 7f26a503c..5a2dc9bd4 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -27,14 +27,14 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @brief Constructor * @note prescaler is set as 300. * @param [in] clock_generator: Clock generator - * @param [in] sils_port_id: Port ID for communication line b/w OBC - * @param [in] obc: The communication target OBC + * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer + * @param [in] obc: The communication target OnBoardComputer * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager * @param [in] mode_id: Mode ID to select sender(0) or responder(1) */ - ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OBC* obc, const unsigned int hils_port_id, + ExampleSerialCommunicationForHils(ClockGenerator* clock_generator, const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager, const int mode_id); /** * @fn ~ExampleSerialCommunicationForHils @@ -61,12 +61,12 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica // Override functions for ObcComunication /** * @fn ParseCommand - * @brief Parse command received from OBC + * @brief Parse command received from OnBoardComputer */ int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry - * @brief Generate telemetry send to OBC + * @brief Generate telemetry send to OnBoardComputer */ int GenerateTelemetry() override; }; diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index ace07e25f..edccb81e4 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -1,17 +1,17 @@ /** * @file example_serial_communication_with_obc.cpp - * @brief Example of component emulation with communication between OBC Flight software + * @brief Example of component emulation with communication between OnBoardComputer Flight software */ #include "example_serial_communication_with_obc.hpp" #include -ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OBC* obc) +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OnBoardComputer* obc) : Component(1000, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } -ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OBC* obc) +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OnBoardComputer* obc) : Component(prescaler, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 5590d7b51..bcd80bd9c 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file example_serial_communication_with_obc.hpp - * @brief Example of component emulation with communication between OBC Flight software + * @brief Example of component emulation with communication between OnBoardComputer Flight software */ #ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_HPP_P_ @@ -14,7 +14,7 @@ /** * @class ExampleSerialCommunicationWithObc - * @brief Example of component emulation with communication between OBC Flight software + * @brief Example of component emulation with communication between OnBoardComputer Flight software * @details Command to EXP is 5 bytes. * - The first 3 bytes: "SET" * - The Fourth byte: Set data (ASCII 0x21~0x7e) @@ -32,19 +32,19 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @brief Constructor without prescaler * @note The prescaler is set as 1000 * @param [in] clock_generator: Clock generator - * @param [in] port_id: Port ID for communication line b/w OBC - * @param [in] obc: The communication target OBC + * @param [in] port_id: Port ID for communication line b/w OnBoardComputer + * @param [in] obc: The communication target OnBoardComputer */ - ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OnBoardComputer* obc); /** * @fn ExampleSerialCommunicationWithObc * @brief Constructor * @param [in] clock_generator: Clock generator - * @param [in] port_id: Port ID for communication line b/w OBC + * @param [in] port_id: Port ID for communication line b/w OnBoardComputer * @param [in] prescaler: Frequency scale factor for update - * @param [in] obc: The communication target OBC + * @param [in] obc: The communication target OnBoardComputer */ - ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OBC* obc); + ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OnBoardComputer* obc); /** * @fn ~SerialCommunicationWithObc * @brief Destructor @@ -73,12 +73,12 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica // Override functions for ObcCommunication /** * @fn ParseCommand - * @brief Parse command received from OBC + * @brief Parse command received from OnBoardComputer */ int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry - * @brief Generate telemetry send to OBC + * @brief Generate telemetry send to OnBoardComputer */ int GenerateTelemetry() override; diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index ca34f1ee0..0ed616fbe 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -67,7 +67,7 @@ class HilsI2cTargetPort : public HilsUartPort { /** * @fn ReadCommand * @brief Read command requested from the COM port to the component - * @param [out] rx_data: Data to the OBC + * @param [out] rx_data: Data to the OnBoardComputer * @param [in] length: Length of the rx_data * @return Length or zero when an error happened */ diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 587786419..54d79582c 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -76,21 +76,21 @@ class I2cPort { */ unsigned char ReadRegister(const unsigned char i2c_address, const unsigned char register_address); - // OBC->Component Command emulation + // OnBoardComputer->Component Command emulation /** * @fn WriteCommand - * @brief Write command requested from an OBC to the component + * @brief Write command requested from an OnBoardComputer to the component * @param [in] i2c_address: I2C address of the target device - * @param [in] tx_data: data from the OBC + * @param [in] tx_data: data from the OnBoardComputer * @param [in] length: length of the tx_data * @return Length or zero when an error happened */ unsigned char WriteCommand(const unsigned char i2c_address, const unsigned char* tx_data, const unsigned char length); /** * @fn ReadCommand - * @brief Read command requested from an OBC to the component + * @brief Read command requested from an OnBoardComputer to the component * @param [in] i2c_address: I2C address of the target device - * @param [out] rx_data: Data to the OBC + * @param [out] rx_data: Data to the OnBoardComputer * @param [in] length: Length of the tx_data * @return Length or zero when an error happened */ @@ -104,7 +104,7 @@ class I2cPort { /** @brief Device register: **/ std::map, unsigned char> device_registers_; - /** @brief Buffer for the command from OBC : **/ + /** @brief Buffer for the command from OnBoardComputer : **/ std::map, unsigned char> command_buffer_; }; diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 51598aec2..24fb28de0 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -23,8 +23,8 @@ class UartPort { /** * @fn UartPort * @brief Constructor - * @param [in] rx_buffer_size: RX(Component -> OBC) buffer size - * @param [in] tx_buffer_size: TX(OBC -> Component) buffer size + * @param [in] rx_buffer_size: RX(Component -> OnBoardComputer) buffer size + * @param [in] tx_buffer_size: TX(OnBoardComputer -> Component) buffer size */ UartPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size); /** @@ -35,7 +35,7 @@ class UartPort { /** * @fn WriteTx - * @brief Write data to the TX buffer from OBC to Component + * @brief Write data to the TX buffer from OnBoardComputer to Component * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) * @param [in] data_length: Length of the data to write @@ -44,7 +44,7 @@ class UartPort { int WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn WriteRx - * @brief Write data to the RX buffer from Component to OBC + * @brief Write data to the RX buffer from Component to OnBoardComputer * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) * @param [in] data_length: Length of the data to write @@ -63,7 +63,7 @@ class UartPort { int ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn ReadRx - * @brief Read data from the TX buffer by OBC + * @brief Read data from the TX buffer by OnBoardComputer * @param [out] buffer: Data buffer to stored the read data * @param [in] offset: Start offset of the buffer to read (usually zero) * @param [in] data_length: Length of the data to read @@ -74,8 +74,8 @@ class UartPort { private: const static unsigned int kDefaultBufferSize = 1024; //!< Default buffer size - RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OBC) - RingBuffer* tx_buffer_; //!< Transmit buffer (OBC -> Component) + RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OnBoardComputer) + RingBuffer* tx_buffer_; //!< Transmit buffer (OnBoardComputer -> Component) }; #endif // S2E_COMPONENTS_PORTS_UART_PORT_HPP_ diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index 88e04c42c..652739919 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -4,25 +4,28 @@ */ #include "on_board_computer.hpp" -OBC::OBC(ClockGenerator* clock_generator) : Component(1, clock_generator) { Initialize(); } +OnBoardComputer::OnBoardComputer(ClockGenerator* clock_generator) : Component(1, clock_generator) { Initialize(); } -OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port) : Component(prescaler, clock_generator, power_port) { Initialize(); } +OnBoardComputer::OnBoardComputer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port) + : Component(prescaler, clock_generator, power_port) { + Initialize(); +} -OBC::OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, - const double assumed_power_consumption_W) +OnBoardComputer::OnBoardComputer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, + const double assumed_power_consumption_W) : Component(prescaler, clock_generator, power_port) { power_port_->SetMinimumVoltage_V(minimum_voltage_V); power_port_->SetAssumedPowerConsumption_W(assumed_power_consumption_W); Initialize(); } -OBC::~OBC() {} +OnBoardComputer::~OnBoardComputer() {} -void OBC::Initialize() {} +void OnBoardComputer::Initialize() {} -void OBC::MainRoutine(const int time_count) { UNUSED(time_count); } +void OnBoardComputer::MainRoutine(const int time_count) { UNUSED(time_count); } -int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { +int OnBoardComputer::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { if (uart_ports_[port_id] != nullptr) { // Port already used return -1; @@ -32,7 +35,7 @@ int OBC::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { } // Close port and free resources -int OBC::CloseComPort(int port_id) { +int OnBoardComputer::CloseComPort(int port_id) { // Port not used if (uart_ports_[port_id] == nullptr) return -1; @@ -42,31 +45,31 @@ int OBC::CloseComPort(int port_id) { return 0; } -int OBC::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { +int OnBoardComputer::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->WriteTx(buffer, offset, length); } -int OBC::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { +int OnBoardComputer::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->ReadTx(buffer, offset, length); } -int OBC::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { +int OnBoardComputer::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->WriteRx(buffer, offset, length); } -int OBC::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { +int OnBoardComputer::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; return port->ReadRx(buffer, offset, length); } -int OBC::I2cConnectPort(int port_id, const unsigned char i2c_address) { +int OnBoardComputer::I2cConnectPort(int port_id, const unsigned char i2c_address) { if (i2c_ports_[port_id] != nullptr) { // Port already used } else { @@ -77,7 +80,7 @@ int OBC::I2cConnectPort(int port_id, const unsigned char i2c_address) { return 0; } -int OBC::I2cCloseComPort(int port_id) { +int OnBoardComputer::I2cCloseComPort(int port_id) { // Port not used if (i2c_ports_[port_id] == nullptr) return -1; @@ -87,29 +90,29 @@ int OBC::I2cCloseComPort(int port_id) { return 0; } -int OBC::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, - const unsigned char length) { +int OnBoardComputer::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, + const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < length; i++) { i2c_port->WriteRegister(i2c_address, reg_address, data[i]); } return 0; } -int OBC::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, - const unsigned char length) { +int OnBoardComputer::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < length; i++) { data[i] = i2c_port->ReadRegister(reg_address, i2c_address); } return 0; } -int OBC::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { +int OnBoardComputer::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; i2c_port->ReadCommand(i2c_address, data, length); return 0; } -int OBC::GpioConnectPort(int port_id) { +int OnBoardComputer::GpioConnectPort(int port_id) { if (gpio_ports_[port_id] != nullptr) { // Port already used return -1; @@ -118,13 +121,13 @@ int OBC::GpioConnectPort(int port_id) { return 0; } -int OBC::GpioComponentWrite(int port_id, const bool is_high) { +int OnBoardComputer::GpioComponentWrite(int port_id, const bool is_high) { GpioPort* port = gpio_ports_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } -bool OBC::GpioComponentRead(int port_id) { +bool OnBoardComputer::GpioComponentRead(int port_id) { GpioPort* port = gpio_ports_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index a12c232cc..5c943d261 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -14,28 +14,28 @@ #include "../../base/component.hpp" /* - * @class OBC + * @class OnBoardComputer * @brief Class to emulate on board computer - * @note OBC is connected with other components to communicate, and flight software is executed in OBC. + * @note OnBoardComputer is connected with other components to communicate, and flight software is executed in OnBoardComputer. */ -class OBC : public Component { +class OnBoardComputer : public Component { public: /** - * @fn OBC + * @fn OnBoardComputer * @brief Constructor * @param [in] clock_generator: Clock generator */ - OBC(ClockGenerator* clock_generator); + OnBoardComputer(ClockGenerator* clock_generator); /** - * @fn OBC + * @fn OnBoardComputer * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] power_port: Power port */ - OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port); + OnBoardComputer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port); /** - * @fn OBC + * @fn OnBoardComputer * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator @@ -43,34 +43,34 @@ class OBC : public Component { * @param [in] minimum_voltage_V: Minimum voltage [V] * @param [in] assumed_power_consumption_W: Assumed power consumption [W] */ - OBC(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, - const double assumed_power_consumption_W); + OnBoardComputer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const double minimum_voltage_V, + const double assumed_power_consumption_W); /** - * @fn ~OBC + * @fn ~OnBoardComputer * @brief Destructor */ - virtual ~OBC(); + virtual ~OnBoardComputer(); // UART Communication port functions. TODO:Rename the following functions to UartHogeHoge /** * @fn ConnectComPort - * @brief Connect UART communication port between OBC and a component + * @brief Connect UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID - * @param [in] tx_buffer_size: TX (OBC -> Component) buffer size - * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX (OnBoardComputer -> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OnBoardComputer) buffer size * @return -1: error, 0: success */ virtual int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size); /** * @fn ConnectComPort - * @brief Close UART communication port between OBC and a component + * @brief Close UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ virtual int CloseComPort(int port_id); /** * @fn SendFromObc - * @brief Send data from OBC to Components with UART used by OBC side. + * @brief Send data from OnBoardComputer to Components with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -80,7 +80,7 @@ class OBC : public Component { virtual int SendFromObc(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByCompo - * @brief Read data from OBC to Components with UART used by component side. + * @brief Read data from OnBoardComputer to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -91,7 +91,7 @@ class OBC : public Component { /** * @fn SendFromComponent - * @brief Send data from component to OBC with UART used by component side. + * @brief Send data from component to OnBoardComputer with UART used by component side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -101,7 +101,7 @@ class OBC : public Component { virtual int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc - * @brief Read data from component to OBC with UART used by OBC side. + * @brief Read data from component to OnBoardComputer with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -113,7 +113,7 @@ class OBC : public Component { // I2C Communication port functions /** * @fn I2cConnectPort - * @brief Connect I2C communication port between OBC (I2C controller) and a component (I2C target) + * @brief Connect I2C communication port between OnBoardComputer (I2C controller) and a component (I2C target) * @note Multiple target can be connected to one port ID * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of target device @@ -122,7 +122,7 @@ class OBC : public Component { virtual int I2cConnectPort(int port_id, const unsigned char i2c_address); /** * @fn I2cCloseComPort - * @brief Close I2C communication port between OBC and a component + * @brief Close I2C communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ @@ -153,7 +153,7 @@ class OBC : public Component { const unsigned char length); /** * @fn I2cComponentReadCommand - * @brief Read command from OBC to target device's register + * @brief Read command from OnBoardComputer to target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer @@ -165,7 +165,7 @@ class OBC : public Component { // GPIO port functions /** * @fn GpioConnectPort - * @brief Connect GPIO communication port between OBC and a component + * @brief Connect GPIO communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index c78443d73..a4f57d457 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -16,16 +16,16 @@ std::map OBC_C2A::com_ports_c2a_; std::map OBC_C2A::i2c_com_ports_c2a_; std::map OBC_C2A::gpio_ports_c2a_; -OBC_C2A::OBC_C2A(ClockGenerator* clock_generator) : OBC(clock_generator), timing_regulator_(1) { +OBC_C2A::OBC_C2A(ClockGenerator* clock_generator) : OnBoardComputer(clock_generator), timing_regulator_(1) { // Initialize(); } -OBC_C2A::OBC_C2A(ClockGenerator* clock_generator, int timing_regulator) : OBC(clock_generator), timing_regulator_(timing_regulator) { +OBC_C2A::OBC_C2A(ClockGenerator* clock_generator, int timing_regulator) : OnBoardComputer(clock_generator), timing_regulator_(timing_regulator) { // Initialize(); } OBC_C2A::OBC_C2A(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port) - : OBC(prescaler, clock_generator, power_port), timing_regulator_(timing_regulator) { + : OnBoardComputer(prescaler, clock_generator, power_port), timing_regulator_(timing_regulator) { // Initialize(); } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 8fb651bb4..a1f387101 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -14,7 +14,7 @@ * @class OBC_C2A * @brief Class to emulate on board computer with C2A flight software */ -class OBC_C2A : public OBC { +class OBC_C2A : public OnBoardComputer { public: /** * @fn OBC_C2A @@ -47,23 +47,23 @@ class OBC_C2A : public OBC { // UART Communication port functions. TODO:Rename the following functions to UartHogeHoge /** * @fn ConnectComPort - * @brief Connect UART communication port between OBC and a component + * @brief Connect UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID - * @param [in] tx_buffer_size: TX (OBC -> Component) buffer size - * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX (OnBoardComputer -> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OnBoardComputer) buffer size * @return -1: error, 0: success */ int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) override; /** * @fn ConnectComPort - * @brief Close UART communication port between OBC and a component + * @brief Close UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ int CloseComPort(int port_id) override; /** * @fn SendFromObc - * @brief Send data from OBC to Components with UART used by OBC side. + * @brief Send data from OnBoardComputer to Components with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -73,7 +73,7 @@ class OBC_C2A : public OBC { int SendFromObc(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByCompo - * @brief Read data from OBC to Components with UART used by component side. + * @brief Read data from OnBoardComputer to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -84,7 +84,7 @@ class OBC_C2A : public OBC { /** * @fn SendFromComponent - * @brief Send data from component to OBC with UART used by component side. + * @brief Send data from component to OnBoardComputer with UART used by component side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -94,7 +94,7 @@ class OBC_C2A : public OBC { int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByObc - * @brief Read data from component to OBC with UART used by OBC side. + * @brief Read data from component to OnBoardComputer with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -106,7 +106,7 @@ class OBC_C2A : public OBC { // Static function for C2A /** * @fn SendFromObc_C2A - * @brief Send data from OBC to Components with UART used by C2A flight software + * @brief Send data from OnBoardComputer to Components with UART used by C2A flight software * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -116,7 +116,7 @@ class OBC_C2A : public OBC { static int SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc_C2A - * @brief Read data from component to OBC with UART used by C2A flight software + * @brief Read data from component to OnBoardComputer with UART used by C2A flight software * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -128,7 +128,7 @@ class OBC_C2A : public OBC { // I2C /** * @fn I2cConnectPort - * @brief Connect I2C communication port between OBC (I2C controller) and a component (I2C target) + * @brief Connect I2C communication port between OnBoardComputer (I2C controller) and a component (I2C target) * @note Multiple target can be connected to one port ID * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of target device @@ -138,7 +138,7 @@ class OBC_C2A : public OBC { int I2cConnectPort(int port_id, const unsigned char i2c_address) override; /** * @fn I2cCloseComPort - * @brief Close I2C communication port between OBC and a component + * @brief Close I2C communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ @@ -169,7 +169,7 @@ class OBC_C2A : public OBC { const unsigned char length) override; /** * @fn I2cComponentReadCommand - * @brief Read command from OBC to target device's register + * @brief Read command from OnBoardComputer to target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer @@ -213,7 +213,7 @@ class OBC_C2A : public OBC { // GPIO /** * @fn GpioConnectPort - * @brief Connect GPIO communication port between OBC and a component + * @brief Connect GPIO communication port between OnBoardComputer and a component * @param [in] port_id: Port ID * @return -1: error, 0: success */ diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index e0dbe6839..a8c5d1fe5 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -47,7 +47,7 @@ class HilsPortManager { virtual int UartCloseComPort(unsigned int port_id); /** * @fn UartReceive - * @brief UART data receive from COM port (ex. OBC) to components in S2E + * @brief UART data receive from COM port (ex. OnBoardComputer) to components in S2E * @param [in] port_id: COM port ID * @param [out] buffer: Data buffer to receive * @param [in] offset: Start offset for the data buffer to receive @@ -56,7 +56,7 @@ class HilsPortManager { virtual int UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int count); /** * @fn UartSend - * @brief UART data send from components in S2E to COM port (ex. OBC) + * @brief UART data send from components in S2E to COM port (ex. OnBoardComputer) * @param [in] port_id: COM port ID * @param [in] buffer: Data buffer to send * @param [in] offset: Start offset for the data buffer to send diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 05d3344fe..4f5b0d568 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -16,12 +16,12 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // PCU power port connection pcu_ = new PowerControlUnit(clock_gen); - pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here + pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OnBoardComputer: assumed power consumption is defined here pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyroSensor pcu_->ConnectPort(2, 1.0); // for other all components // Components - obc_ = new OBC(1, clock_gen, pcu_->GetPowerPort(0)); + obc_ = new OnBoardComputer(1, clock_gen, pcu_->GetPowerPort(0)); hils_port_manager_ = new HilsPortManager(); // GyroSensor diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 5f2a8bbfe..60d70023c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -30,7 +30,7 @@ #include "../installed_components.hpp" -class OBC; +class OnBoardComputer; class PowerControlUnit; class GyroSensor; class Magnetometer; @@ -83,7 +83,7 @@ class SampleComponents : public InstalledComponents { private: PowerControlUnit* pcu_; //!< Power Control Unit - OBC* obc_; //!< Onboard Computer + OnBoardComputer* obc_; //!< Onboard Computer HilsPortManager* hils_port_manager_; //!< Port manager for HILS test // AOCS From dbf4f727ce2cc3a1b69d3ac24e0a4ae35e2b0a30 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:40:15 +0100 Subject: [PATCH 0866/1086] Rename OBC_C2A to ObcWithC2a --- .../real/cdh/on_board_computer_with_c2a.cpp | 83 ++++++++++--------- .../real/cdh/on_board_computer_with_c2a.hpp | 20 ++--- 2 files changed, 52 insertions(+), 51 deletions(-) diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index a4f57d457..45a11dd86 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -12,26 +12,27 @@ #include "src_core/c2a_core_main.h" #endif -std::map OBC_C2A::com_ports_c2a_; -std::map OBC_C2A::i2c_com_ports_c2a_; -std::map OBC_C2A::gpio_ports_c2a_; +std::map ObcWithC2a::com_ports_c2a_; +std::map ObcWithC2a::i2c_com_ports_c2a_; +std::map ObcWithC2a::gpio_ports_c2a_; -OBC_C2A::OBC_C2A(ClockGenerator* clock_generator) : OnBoardComputer(clock_generator), timing_regulator_(1) { +ObcWithC2a::ObcWithC2a(ClockGenerator* clock_generator) : OnBoardComputer(clock_generator), timing_regulator_(1) { // Initialize(); } -OBC_C2A::OBC_C2A(ClockGenerator* clock_generator, int timing_regulator) : OnBoardComputer(clock_generator), timing_regulator_(timing_regulator) { +ObcWithC2a::ObcWithC2a(ClockGenerator* clock_generator, int timing_regulator) + : OnBoardComputer(clock_generator), timing_regulator_(timing_regulator) { // Initialize(); } -OBC_C2A::OBC_C2A(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port) +ObcWithC2a::ObcWithC2a(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port) : OnBoardComputer(prescaler, clock_generator, power_port), timing_regulator_(timing_regulator) { // Initialize(); } -OBC_C2A::~OBC_C2A() {} +ObcWithC2a::~ObcWithC2a() {} -void OBC_C2A::Initialize() { +void ObcWithC2a::Initialize() { #ifdef USE_C2A TMGR_init(); // Time Manager // Initialize at the beginning in order to measure the execution @@ -44,7 +45,7 @@ void OBC_C2A::Initialize() { #endif } -void OBC_C2A::MainRoutine(const int time_count) { +void ObcWithC2a::MainRoutine(const int time_count) { UNUSED(time_count); #ifdef USE_C2A @@ -61,7 +62,7 @@ void OBC_C2A::MainRoutine(const int time_count) { } // Override functions -int OBC_C2A::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { +int ObcWithC2a::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) { if (com_ports_c2a_[port_id] != nullptr) { // Port already used return -1; @@ -71,7 +72,7 @@ int OBC_C2A::ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) } // Close port and free resources -int OBC_C2A::CloseComPort(int port_id) { +int ObcWithC2a::CloseComPort(int port_id) { // Port not used if (com_ports_c2a_[port_id] == nullptr) return -1; @@ -81,33 +82,33 @@ int OBC_C2A::CloseComPort(int port_id) { return 0; } -int OBC_C2A::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { - return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, length); +int ObcWithC2a::SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { + return ObcWithC2a::SendFromObc_C2A(port_id, buffer, offset, length); } -int OBC_C2A::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { +int ObcWithC2a::ReceivedByCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->ReadTx(buffer, offset, length); } -int OBC_C2A::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { +int ObcWithC2a::SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->WriteRx(buffer, offset, length); } -int OBC_C2A::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { - return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, length); +int ObcWithC2a::ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { + return ObcWithC2a::ReceivedByObc_C2A(port_id, buffer, offset, length); } // Static functions -int OBC_C2A::SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { +int ObcWithC2a::SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->WriteTx(buffer, offset, length); } -int OBC_C2A::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { +int ObcWithC2a::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, int length) { UartPort* port = com_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->ReadRx(buffer, offset, length); @@ -116,13 +117,13 @@ int OBC_C2A::ReceivedByObc_C2A(int port_id, unsigned char* buffer, int offset, i // If the character encoding of C2A is UTF-8, these functions are not necessary, // and users can directory use SendFromObc_C2A and ReceivedByObc_C2A int OBC_C2A_SendFromObc(int port_id, unsigned char* buffer, int offset, int length) { - return OBC_C2A::SendFromObc_C2A(port_id, buffer, offset, length); + return ObcWithC2a::SendFromObc_C2A(port_id, buffer, offset, length); } int OBC_C2A_ReceivedByObc(int port_id, unsigned char* buffer, int offset, int length) { - return OBC_C2A::ReceivedByObc_C2A(port_id, buffer, offset, length); + return ObcWithC2a::ReceivedByObc_C2A(port_id, buffer, offset, length); } -int OBC_C2A::I2cConnectPort(int port_id, const unsigned char i2c_address) { +int ObcWithC2a::I2cConnectPort(int port_id, const unsigned char i2c_address) { if (i2c_com_ports_c2a_[port_id] != nullptr) { // Port already used } else { @@ -133,7 +134,7 @@ int OBC_C2A::I2cConnectPort(int port_id, const unsigned char i2c_address) { return 0; } -int OBC_C2A::I2cCloseComPort(int port_id) { +int ObcWithC2a::I2cCloseComPort(int port_id) { // Port not used if (i2c_com_ports_c2a_[port_id] == nullptr) return -1; @@ -143,13 +144,13 @@ int OBC_C2A::I2cCloseComPort(int port_id) { return 0; } -int OBC_C2A::I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { +int ObcWithC2a::I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; i2c_port->WriteCommand(i2c_address, data, length); return 0; } -int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { +int ObcWithC2a::I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; if (length == 1) { @@ -162,7 +163,7 @@ int OBC_C2A::I2cWriteRegister(int port_id, const unsigned char i2c_address, cons return 0; } -int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { +int ObcWithC2a::I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (int i = 0; i < length; i++) { data[i] = i2c_port->ReadRegister(i2c_address); @@ -170,39 +171,39 @@ int OBC_C2A::I2cReadRegister(int port_id, const unsigned char i2c_address, unsig return 0; } -int OBC_C2A::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, - const unsigned char length) { +int ObcWithC2a::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < length; i++) { i2c_port->WriteRegister(i2c_address, reg_address + i, data[i]); } return 0; } -int OBC_C2A::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, - const unsigned char length) { +int ObcWithC2a::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < length; i++) { data[i] = i2c_port->ReadRegister(i2c_address, reg_address + i); } return 0; } -int OBC_C2A::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { +int ObcWithC2a::I2cComponentReadCommand(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; i2c_port->ReadCommand(i2c_address, data, length); return 0; } int OBC_C2A_I2cWriteCommand(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { - return OBC_C2A::I2cWriteCommand(port_id, i2c_address, data, length); + return ObcWithC2a::I2cWriteCommand(port_id, i2c_address, data, length); } int OBC_C2A_I2cWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char* data, const unsigned char length) { - return OBC_C2A::I2cWriteRegister(port_id, i2c_address, data, length); + return ObcWithC2a::I2cWriteRegister(port_id, i2c_address, data, length); } int OBC_C2A_I2cReadRegister(int port_id, const unsigned char i2c_address, unsigned char* data, const unsigned char length) { - return OBC_C2A::I2cReadRegister(port_id, i2c_address, data, length); + return ObcWithC2a::I2cReadRegister(port_id, i2c_address, data, length); } -int OBC_C2A::GpioConnectPort(int port_id) { +int ObcWithC2a::GpioConnectPort(int port_id) { if (gpio_ports_c2a_[port_id] != nullptr) { // Port already used return -1; @@ -211,30 +212,30 @@ int OBC_C2A::GpioConnectPort(int port_id) { return 0; } -int OBC_C2A::GpioComponentWrite(int port_id, const bool is_high) { +int ObcWithC2a::GpioComponentWrite(int port_id, const bool is_high) { GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } -bool OBC_C2A::GpioComponentRead(int port_id) { +bool ObcWithC2a::GpioComponentRead(int port_id) { GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); } -int OBC_C2A::GpioWrite_C2A(int port_id, const bool is_high) { +int ObcWithC2a::GpioWrite_C2A(int port_id, const bool is_high) { GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return -1; return port->DigitalWrite(is_high); } -bool OBC_C2A::GpioRead_C2A(int port_id) { +bool ObcWithC2a::GpioRead_C2A(int port_id) { GpioPort* port = gpio_ports_c2a_[port_id]; if (port == nullptr) return false; return port->DigitalRead(); } -int OBC_C2A_GpioWrite(int port_id, const bool is_high) { return OBC_C2A::GpioWrite_C2A(port_id, is_high); } +int OBC_C2A_GpioWrite(int port_id, const bool is_high) { return ObcWithC2a::GpioWrite_C2A(port_id, is_high); } -bool OBC_C2A_GpioRead(int port_id) { return OBC_C2A::GpioRead_C2A(port_id); } \ No newline at end of file +bool OBC_C2A_GpioRead(int port_id) { return ObcWithC2a::GpioRead_C2A(port_id); } \ No newline at end of file diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index a1f387101..e03a3a4d0 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -11,38 +11,38 @@ #include "on_board_computer.hpp" /* - * @class OBC_C2A + * @class ObcWithC2a * @brief Class to emulate on board computer with C2A flight software */ -class OBC_C2A : public OnBoardComputer { +class ObcWithC2a : public OnBoardComputer { public: /** - * @fn OBC_C2A + * @fn ObcWithC2a * @brief Constructor * @param [in] clock_generator: Clock generator */ - OBC_C2A(ClockGenerator* clock_generator); + ObcWithC2a(ClockGenerator* clock_generator); /** - * @fn OBC_C2A + * @fn ObcWithC2a * @brief Constructor * @param [in] clock_generator: Clock generator * @param [in] timing_regulator: Timing regulator to update flight software faster than the component update */ - OBC_C2A(ClockGenerator* clock_generator, int timing_regulator); + ObcWithC2a(ClockGenerator* clock_generator, int timing_regulator); /** - * @fn OBC_C2A + * @fn ObcWithC2a * @brief Constructor * @param [in] prescaler: Frequency scale factor for update * @param [in] clock_generator: Clock generator * @param [in] timing_regulator: Timing regulator to update flight software faster than the component update * @param [in] power_port: Power port */ - OBC_C2A(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port); + ObcWithC2a(int prescaler, ClockGenerator* clock_generator, int timing_regulator, PowerPort* power_port); /** - * @fn ~OBC_C2A + * @fn ~ObcWithC2a * @brief Destructor */ - ~OBC_C2A(); + ~ObcWithC2a(); // UART Communication port functions. TODO:Rename the following functions to UartHogeHoge /** From bd6b22edf4553cae45df23096220d2017e3b6997 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:47:07 +0100 Subject: [PATCH 0867/1086] Fix format --- src/components/base/i2c_target_communication_with_obc.cpp | 3 ++- src/components/base/i2c_target_communication_with_obc.hpp | 6 +++--- src/components/base/uart_communication_with_obc.cpp | 4 ++-- src/components/base/uart_communication_with_obc.hpp | 5 +++-- src/components/examples/example_i2c_target_for_hils.hpp | 4 ++-- .../examples/example_serial_communication_with_obc.cpp | 3 ++- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- 7 files changed, 15 insertions(+), 12 deletions(-) diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index ea5cf34e6..2501c46f4 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -33,7 +33,8 @@ I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int } I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, - const unsigned char i2c_address, OnBoardComputer* obc, HilsPortManager* hils_port_manager) + const unsigned char i2c_address, OnBoardComputer* obc, + HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), i2c_address_(i2c_address), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::HILS; diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 9297fed45..4e7df79e0 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -42,8 +42,8 @@ class I2cTargetCommunicationWithObc { * @param [in] obc: The communication target OnBoardComputer * @param [in] hils_port_manager: HILS port manager */ - I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, OnBoardComputer* obc, - HilsPortManager* hils_port_manager); + I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, + OnBoardComputer* obc, HilsPortManager* hils_port_manager); /** * @fn I2cTargetCommunicationWithObc * @brief Prevent double freeing of memory when this class is copied @@ -117,7 +117,7 @@ class I2cTargetCommunicationWithObc { OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OnBoardComputer* obc_; //!< Communication target OnBoardComputer + OnBoardComputer* obc_; //!< Communication target OnBoardComputer HilsPortManager* hils_port_manager_; //!< HILS port manager }; diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index 373da17e4..b3a14c8d1 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -64,8 +64,8 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_ InitializeObcComBase(); } -UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, const unsigned int baud_rate, - HilsPortManager* hils_port_manager) +UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OnBoardComputer* obc, const unsigned int hils_port_id, + const unsigned int baud_rate, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), baud_rate_(baud_rate), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS simulation_mode_ = OBC_COM_UART_MODE::HILS; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 09249e2bb..33d05c557 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -44,7 +44,8 @@ class UartCommunicationWithObc { * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size * @param [in] obc: The communication target OnBoardComputer */ - UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OnBoardComputer* obc); + UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, + OnBoardComputer* obc); /** * @fn UartCommunicationWithObc * @brief Constructor for HILS mode @@ -106,7 +107,7 @@ class UartCommunicationWithObc { OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OnBoardComputer* obc_; //!< Communication target OnBoardComputer + OnBoardComputer* obc_; //!< Communication target OnBoardComputer HilsPortManager* hils_port_manager_; //!< HILS port manager /** diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index da182c7af..1cf5e8a0b 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -32,8 +32,8 @@ class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationW * @param [in] hils_port_id: ID of HILS communication port * @param [in] hils_port_manager: HILS port manager */ - ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, unsigned char i2c_address, OnBoardComputer* obc, - const unsigned int hils_port_id, HilsPortManager* hils_port_manager); + ExampleI2cTargetForHils(const int prescaler, ClockGenerator* clock_generator, const int sils_port_id, unsigned char i2c_address, + OnBoardComputer* obc, const unsigned int hils_port_id, HilsPortManager* hils_port_manager); /** * @fn ~ExampleI2cTargetForHils * @brief Destructor diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index edccb81e4..257bc55a5 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -11,7 +11,8 @@ ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenera : Component(1000, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } -ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OnBoardComputer* obc) +ExampleSerialCommunicationWithObc::ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, + OnBoardComputer* obc) : Component(prescaler, clock_generator), UartCommunicationWithObc(port_id, obc) { Initialize(); } diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 60d70023c..4b3bd9f04 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -83,7 +83,7 @@ class SampleComponents : public InstalledComponents { private: PowerControlUnit* pcu_; //!< Power Control Unit - OnBoardComputer* obc_; //!< Onboard Computer + OnBoardComputer* obc_; //!< Onboard Computer HilsPortManager* hils_port_manager_; //!< Port manager for HILS test // AOCS From f2abc9d6aa72f3b082ac9ac12008831b99334a98 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:54:12 +0100 Subject: [PATCH 0868/1086] Fix comments --- src/components/base/gpio_connection_with_obc.cpp | 2 +- src/components/base/gpio_connection_with_obc.hpp | 14 +++++++------- src/components/base/i2c_controller.hpp | 2 +- .../base/i2c_target_communication_with_obc.cpp | 2 +- .../base/i2c_target_communication_with_obc.hpp | 4 ++-- .../base/uart_communication_with_obc.cpp | 2 +- .../base/uart_communication_with_obc.hpp | 4 ++-- 7 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/components/base/gpio_connection_with_obc.cpp b/src/components/base/gpio_connection_with_obc.cpp index 3ef349ad1..7a3024a66 100644 --- a/src/components/base/gpio_connection_with_obc.cpp +++ b/src/components/base/gpio_connection_with_obc.cpp @@ -1,6 +1,6 @@ /** * @file gpio_connection_with_obc.cpp - * @brief Base class for GPIO communication with OnBoardComputer flight software + * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index 43c47a376..7e3c5fb0b 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file gpio_connection_with_obc.hpp - * @brief Base class for GPIO communication with OnBoardComputer flight software + * @brief Base class for GPIO communication with OBC flight software * TODO: consider relation with IGPIOCompo */ @@ -11,8 +11,8 @@ /** * @class GpioConnectionWithObc - * @brief Base class for GPIO communication with OnBoardComputer flight software - * @note Components which want to communicate with OnBoardComputer using GPIO have to inherit this. + * @brief Base class for GPIO communication with OBC flight software + * @note Components which want to communicate with OBC using GPIO have to inherit this. */ class GpioConnectionWithObc { public: @@ -20,7 +20,7 @@ class GpioConnectionWithObc { * @fn GpioConnectionWithObc * @brief Constructor for SILS mode * @param [in] port_id: Port ID GPIO line - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ GpioConnectionWithObc(const std::vector port_id, OnBoardComputer* obc); /** @@ -33,21 +33,21 @@ class GpioConnectionWithObc { /** * @fn Read * @brief Read the GPIO state - * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OnBoardComputer. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC * @return High(True) or Low(False) of GPIO state */ bool Read(const int index); /** * @fn Write * @brief Write the GPIO state - * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OnBoardComputer. + * @param [in] index: element index for port_id_ vector, not the GPIO port ID for OBC * @param [in] is_high: High(True) or Low(False) of GPIO state */ void Write(const int index, const bool is_high); private: std::vector port_id_; //!< Port ID GPIO line - OnBoardComputer* obc_; //!< The communication target OnBoardComputer + OnBoardComputer* obc_; //!< The communication target OBC }; #endif // S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 4b1ed1d64..7475b91db 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -12,7 +12,7 @@ /** * @class I2cController * @brief This class simulates the I2C Controller communication with the I2C Target. - * @note Generally, I2C controller side is OnBoardComputer, and components are target side. + * @note Generally, I2C controller side is OBC, and components are target side. * The main purpose is to validate the emulated I2C Target component in the HILS test. * This class works only HILS mode */ diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index 2501c46f4..b3938f75c 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -1,6 +1,6 @@ /** * @file i2c_target_communication_with_obc.cpp - * @brief Base class for I2C communication as target side with OnBoardComputer flight software + * @brief Base class for I2C communication as target side with OBC flight software */ #include "i2c_target_communication_with_obc.hpp" diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 4e7df79e0..4f5236632 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file i2c_target_communication_with_obc.hpp - * @brief Base class for I2C communication as target side with OnBoardComputer flight software + * @brief Base class for I2C communication as target side with OBC flight software */ #ifndef S2E_COMPONENTS_BASE_I2C_TARGET_COMMUNICATION_WITH_OBC_HPP_ @@ -12,7 +12,7 @@ /** * @class I2cTargetCommunicationWithObc - * @brief Base class for I2C communication as target side with OnBoardComputer flight software + * @brief Base class for I2C communication as target side with OBC flight software * @note Generally, components are the target side of I2C (OnBoardComputer is the controller side). */ class I2cTargetCommunicationWithObc { diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index b3a14c8d1..365decfb1 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -1,6 +1,6 @@ /** * @file uart_communication_with_obc.cpp - * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software + * @brief Base class for serial communication (e.g., UART) with OBC flight software */ #include "uart_communication_with_obc.hpp" diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 33d05c557..2d3024e97 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file uart_communication_with_obc.hpp - * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software + * @brief Base class for serial communication (e.g., UART) with OBC flight software */ #ifndef S2E_COMPONENTS_BASE_UART_COMMUNICATION_WITH_OBC_HPP_ @@ -23,7 +23,7 @@ enum class OBC_COM_UART_MODE { /** * @class UartCommunicationWithObc - * @brief Base class for serial communication (e.g., UART) with OnBoardComputer flight software + * @brief Base class for serial communication (e.g., UART) with OBC flight software * @note Components which want to communicate with OnBoardComputer using serial communication have to inherit this. */ class UartCommunicationWithObc { From 34b1c788d74732a873e32dd7006f427b7019876b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:55:01 +0100 Subject: [PATCH 0869/1086] Fix comments --- src/components/base/i2c_target_communication_with_obc.hpp | 6 +++--- src/components/base/uart_communication_with_obc.hpp | 8 ++++---- src/components/examples/example_i2c_target_for_hils.hpp | 2 +- .../examples/example_serial_communication_for_hils.hpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 4 ++-- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 4f5236632..4556e3c6c 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -22,7 +22,7 @@ class I2cTargetCommunicationWithObc { * @brief Constructor for SILS mode * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode * @param [in] i2c_address: I2C address for the target - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OnBoardComputer* obc); /** @@ -39,7 +39,7 @@ class I2cTargetCommunicationWithObc { * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] i2c_address: I2C address for the target - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC * @param [in] hils_port_manager: HILS port manager */ I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned int hils_port_id, const unsigned char i2c_address, @@ -117,7 +117,7 @@ class I2cTargetCommunicationWithObc { OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OnBoardComputer* obc_; //!< Communication target OnBoardComputer + OnBoardComputer* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager }; diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 2d3024e97..24ab95581 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -33,7 +33,7 @@ class UartCommunicationWithObc { * @brief Constructor for SILS mode * @note Default buffer size is used * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ UartCommunicationWithObc(const unsigned int sils_port_id, OnBoardComputer* obc); /** @@ -42,7 +42,7 @@ class UartCommunicationWithObc { * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode * @param [in] tx_buffer_size: TX (Component to OnBoardComputer) buffer size * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, OnBoardComputer* obc); @@ -71,7 +71,7 @@ class UartCommunicationWithObc { * @brief Constructor for both SILS and HILS mode * @note Default buffer size is used * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager @@ -107,7 +107,7 @@ class UartCommunicationWithObc { OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode - OnBoardComputer* obc_; //!< Communication target OnBoardComputer + OnBoardComputer* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager /** diff --git a/src/components/examples/example_i2c_target_for_hils.hpp b/src/components/examples/example_i2c_target_for_hils.hpp index 1cf5e8a0b..9c486995f 100644 --- a/src/components/examples/example_i2c_target_for_hils.hpp +++ b/src/components/examples/example_i2c_target_for_hils.hpp @@ -28,7 +28,7 @@ class ExampleI2cTargetForHils : public Component, public I2cTargetCommunicationW * @param [in] clock_generator: Clock generator * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer * @param [in] i2c_address: I2C address of the target device (This value should be compatible with MFT200XD's setting) - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC * @param [in] hils_port_id: ID of HILS communication port * @param [in] hils_port_manager: HILS port manager */ diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 5a2dc9bd4..1f503a2d0 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -28,7 +28,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica * @note prescaler is set as 300. * @param [in] clock_generator: Clock generator * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port * @param [in] hils_port_manager: HILS port manager diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index bcd80bd9c..5d4607358 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -33,7 +33,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @note The prescaler is set as 1000 * @param [in] clock_generator: Clock generator * @param [in] port_id: Port ID for communication line b/w OnBoardComputer - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, OnBoardComputer* obc); /** @@ -42,7 +42,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @param [in] clock_generator: Clock generator * @param [in] port_id: Port ID for communication line b/w OnBoardComputer * @param [in] prescaler: Frequency scale factor for update - * @param [in] obc: The communication target OnBoardComputer + * @param [in] obc: The communication target OBC */ ExampleSerialCommunicationWithObc(ClockGenerator* clock_generator, int port_id, int prescaler, OnBoardComputer* obc); /** From 401de788a735efb5b6003e0c9cd4d073652ab3f6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 13:57:53 +0100 Subject: [PATCH 0870/1086] Fix comments --- .../base/uart_communication_with_obc.hpp | 12 ++++++------ .../example_serial_communication_for_hils.hpp | 2 +- .../example_serial_communication_with_obc.hpp | 2 +- src/components/ports/i2c_port.hpp | 4 ++-- src/components/ports/uart_port.hpp | 4 ++-- src/components/real/cdh/on_board_computer.hpp | 10 +++++----- .../real/cdh/on_board_computer_with_c2a.hpp | 14 +++++++------- 7 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 24ab95581..231c5f157 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -40,8 +40,8 @@ class UartCommunicationWithObc { * @fn UartCommunicationWithObc * @brief Constructor for SILS mode * @param [in] sils_port_id: Port ID for communication line b/w OnBoardComputer in the SILS mode - * @param [in] tx_buffer_size: TX (Component to OnBoardComputer) buffer size - * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size + * @param [in] tx_buffer_size: TX (Component to OBC) buffer size + * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] obc: The communication target OBC */ UartCommunicationWithObc(const unsigned int sils_port_id, const unsigned int tx_buffer_size, const unsigned int rx_buffer_size, @@ -60,8 +60,8 @@ class UartCommunicationWithObc { * @brief Constructor for HILS mode * @param [in] hils_port_id: ID of HILS communication port * @param [in] baud_rate: Baud rate of HILS communication port - * @param [in] tx_buffer_size: TX (Component to OnBoardComputer) buffer size - * @param [in] rx_buffer_size: RX (OnBoardComputer to Component) buffer size + * @param [in] tx_buffer_size: TX (Component to OBC) buffer size + * @param [in] rx_buffer_size: RX (OBC to Component) buffer size * @param [in] hils_port_manager: HILS port manager */ UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, const unsigned int tx_buffer_size, @@ -101,8 +101,8 @@ class UartCommunicationWithObc { unsigned int sils_port_id_; //!< Port ID for SILS unsigned int hils_port_id_; //!< Port ID for HILS unsigned int baud_rate_; //!< Baudrate for HILS ex. 9600, 115200 - unsigned int tx_buffer_size_; //!< TX (Component to OnBoardComputer) buffer size - unsigned int rx_buffer_size_; //!< RX (OnBoardComputer to Component) buffer size + unsigned int tx_buffer_size_; //!< TX (Component to OBC) buffer size + unsigned int rx_buffer_size_; //!< RX (OBC to Component) buffer size bool is_connected_ = false; //!< Connection flag OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode diff --git a/src/components/examples/example_serial_communication_for_hils.hpp b/src/components/examples/example_serial_communication_for_hils.hpp index 1f503a2d0..1f120699d 100644 --- a/src/components/examples/example_serial_communication_for_hils.hpp +++ b/src/components/examples/example_serial_communication_for_hils.hpp @@ -66,7 +66,7 @@ class ExampleSerialCommunicationForHils : public Component, public UartCommunica int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry - * @brief Generate telemetry send to OnBoardComputer + * @brief Generate telemetry send to OBC */ int GenerateTelemetry() override; }; diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 5d4607358..62290cf72 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -78,7 +78,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica int ParseCommand(const int command_size) override; /** * @fn GenerateTelemetry - * @brief Generate telemetry send to OnBoardComputer + * @brief Generate telemetry send to OBC */ int GenerateTelemetry() override; diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 54d79582c..5a95dd3a7 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -79,7 +79,7 @@ class I2cPort { // OnBoardComputer->Component Command emulation /** * @fn WriteCommand - * @brief Write command requested from an OnBoardComputer to the component + * @brief Write command requested from an OBC to the component * @param [in] i2c_address: I2C address of the target device * @param [in] tx_data: data from the OnBoardComputer * @param [in] length: length of the tx_data @@ -88,7 +88,7 @@ class I2cPort { unsigned char WriteCommand(const unsigned char i2c_address, const unsigned char* tx_data, const unsigned char length); /** * @fn ReadCommand - * @brief Read command requested from an OnBoardComputer to the component + * @brief Read command requested from an OBC to the component * @param [in] i2c_address: I2C address of the target device * @param [out] rx_data: Data to the OnBoardComputer * @param [in] length: Length of the tx_data diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 24fb28de0..19a3dbda0 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -35,7 +35,7 @@ class UartPort { /** * @fn WriteTx - * @brief Write data to the TX buffer from OnBoardComputer to Component + * @brief Write data to the TX buffer from OBC to Component * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) * @param [in] data_length: Length of the data to write @@ -44,7 +44,7 @@ class UartPort { int WriteTx(const unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn WriteRx - * @brief Write data to the RX buffer from Component to OnBoardComputer + * @brief Write data to the RX buffer from Component to OBC * @param [in] buffer: Data buffer to write * @param [in] offset: Start offset of the buffer to write (usually zero) * @param [in] data_length: Length of the data to write diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index 5c943d261..dce51b425 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -70,7 +70,7 @@ class OnBoardComputer : public Component { virtual int CloseComPort(int port_id); /** * @fn SendFromObc - * @brief Send data from OnBoardComputer to Components with UART used by OnBoardComputer side. + * @brief Send data from OBC to Components with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -80,7 +80,7 @@ class OnBoardComputer : public Component { virtual int SendFromObc(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByCompo - * @brief Read data from OnBoardComputer to Components with UART used by component side. + * @brief Read data from OBC to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -91,7 +91,7 @@ class OnBoardComputer : public Component { /** * @fn SendFromComponent - * @brief Send data from component to OnBoardComputer with UART used by component side. + * @brief Send data from component to OBC with UART used by component side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -101,7 +101,7 @@ class OnBoardComputer : public Component { virtual int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc - * @brief Read data from component to OnBoardComputer with UART used by OnBoardComputer side. + * @brief Read data from component to OBC with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -153,7 +153,7 @@ class OnBoardComputer : public Component { const unsigned char length); /** * @fn I2cComponentReadCommand - * @brief Read command from OnBoardComputer to target device's register + * @brief Read command from OBC to target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index e03a3a4d0..715f74033 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -63,7 +63,7 @@ class ObcWithC2a : public OnBoardComputer { int CloseComPort(int port_id) override; /** * @fn SendFromObc - * @brief Send data from OnBoardComputer to Components with UART used by OnBoardComputer side. + * @brief Send data from OBC to Components with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -73,7 +73,7 @@ class ObcWithC2a : public OnBoardComputer { int SendFromObc(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByCompo - * @brief Read data from OnBoardComputer to Components with UART used by component side. + * @brief Read data from OBC to Components with UART used by component side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -84,7 +84,7 @@ class ObcWithC2a : public OnBoardComputer { /** * @fn SendFromComponent - * @brief Send data from component to OnBoardComputer with UART used by component side. + * @brief Send data from component to OBC with UART used by component side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -94,7 +94,7 @@ class ObcWithC2a : public OnBoardComputer { int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByObc - * @brief Read data from component to OnBoardComputer with UART used by OnBoardComputer side. + * @brief Read data from component to OBC with UART used by OnBoardComputer side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -106,7 +106,7 @@ class ObcWithC2a : public OnBoardComputer { // Static function for C2A /** * @fn SendFromObc_C2A - * @brief Send data from OnBoardComputer to Components with UART used by C2A flight software + * @brief Send data from OBC to Components with UART used by C2A flight software * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -116,7 +116,7 @@ class ObcWithC2a : public OnBoardComputer { static int SendFromObc_C2A(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc_C2A - * @brief Read data from component to OnBoardComputer with UART used by C2A flight software + * @brief Read data from component to OBC with UART used by C2A flight software * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer @@ -169,7 +169,7 @@ class ObcWithC2a : public OnBoardComputer { const unsigned char length) override; /** * @fn I2cComponentReadCommand - * @brief Read command from OnBoardComputer to target device's register + * @brief Read command from OBC to target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device * @param [out] data: Write data buffer From 0dd005fd94347e1b7d98d2f01d14c05af47efbbe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:03:41 +0100 Subject: [PATCH 0871/1086] Fix comments --- .../examples/example_serial_communication_with_obc.cpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 4 ++-- src/components/ports/hils_i2c_target_port.hpp | 2 +- src/components/ports/i2c_port.hpp | 6 +++--- src/components/ports/uart_port.cpp | 2 +- 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index 257bc55a5..d9d9c0f31 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -1,6 +1,6 @@ /** * @file example_serial_communication_with_obc.cpp - * @brief Example of component emulation with communication between OnBoardComputer Flight software + * @brief Example of component emulation with communication between OBC flight software */ #include "example_serial_communication_with_obc.hpp" diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 62290cf72..7b86c8833 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -1,6 +1,6 @@ /** * @file example_serial_communication_with_obc.hpp - * @brief Example of component emulation with communication between OnBoardComputer Flight software + * @brief Example of component emulation with communication between OBC flight software */ #ifndef S2E_COMPONENTS_EXAMPLES_EXAMPLE_SERIAL_COMMUNICATION_WITH_OBC_HPP_P_ @@ -14,7 +14,7 @@ /** * @class ExampleSerialCommunicationWithObc - * @brief Example of component emulation with communication between OnBoardComputer Flight software + * @brief Example of component emulation with communication between OBC flight software * @details Command to EXP is 5 bytes. * - The first 3 bytes: "SET" * - The Fourth byte: Set data (ASCII 0x21~0x7e) diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index 0ed616fbe..ca34f1ee0 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -67,7 +67,7 @@ class HilsI2cTargetPort : public HilsUartPort { /** * @fn ReadCommand * @brief Read command requested from the COM port to the component - * @param [out] rx_data: Data to the OnBoardComputer + * @param [out] rx_data: Data to the OBC * @param [in] length: Length of the rx_data * @return Length or zero when an error happened */ diff --git a/src/components/ports/i2c_port.hpp b/src/components/ports/i2c_port.hpp index 5a95dd3a7..57143b992 100644 --- a/src/components/ports/i2c_port.hpp +++ b/src/components/ports/i2c_port.hpp @@ -76,12 +76,12 @@ class I2cPort { */ unsigned char ReadRegister(const unsigned char i2c_address, const unsigned char register_address); - // OnBoardComputer->Component Command emulation + // OBC->Component Command emulation /** * @fn WriteCommand * @brief Write command requested from an OBC to the component * @param [in] i2c_address: I2C address of the target device - * @param [in] tx_data: data from the OnBoardComputer + * @param [in] tx_data: data from the OBC * @param [in] length: length of the tx_data * @return Length or zero when an error happened */ @@ -90,7 +90,7 @@ class I2cPort { * @fn ReadCommand * @brief Read command requested from an OBC to the component * @param [in] i2c_address: I2C address of the target device - * @param [out] rx_data: Data to the OnBoardComputer + * @param [out] rx_data: Data to the OBC * @param [in] length: Length of the tx_data * @return Length or zero when an error happened */ diff --git a/src/components/ports/uart_port.cpp b/src/components/ports/uart_port.cpp index 07eef6358..a2ad5303a 100644 --- a/src/components/ports/uart_port.cpp +++ b/src/components/ports/uart_port.cpp @@ -35,4 +35,4 @@ int UartPort::ReadTx(unsigned char* buffer, const unsigned int offset, const uns int UartPort::ReadRx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length) { return rx_buffer_->Read(buffer, offset, data_length); -} \ No newline at end of file +} From 374952e8ca583a514a83dafa9df8b898ca09be69 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:13:04 +0100 Subject: [PATCH 0872/1086] Fix comments --- src/components/ports/uart_port.hpp | 10 +++++----- src/components/real/cdh/on_board_computer.hpp | 8 ++++---- src/components/real/cdh/on_board_computer_with_c2a.hpp | 8 ++++---- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/components/ports/uart_port.hpp b/src/components/ports/uart_port.hpp index 19a3dbda0..21849aff0 100644 --- a/src/components/ports/uart_port.hpp +++ b/src/components/ports/uart_port.hpp @@ -23,8 +23,8 @@ class UartPort { /** * @fn UartPort * @brief Constructor - * @param [in] rx_buffer_size: RX(Component -> OnBoardComputer) buffer size - * @param [in] tx_buffer_size: TX(OnBoardComputer -> Component) buffer size + * @param [in] rx_buffer_size: RX(Component -> OBC) buffer size + * @param [in] tx_buffer_size: TX(OBC-> Component) buffer size */ UartPort(const unsigned int rx_buffer_size, const unsigned int tx_buffer_size); /** @@ -63,7 +63,7 @@ class UartPort { int ReadTx(unsigned char* buffer, const unsigned int offset, const unsigned int data_length); /** * @fn ReadRx - * @brief Read data from the TX buffer by OnBoardComputer + * @brief Read data from the TX buffer ny OBC * @param [out] buffer: Data buffer to stored the read data * @param [in] offset: Start offset of the buffer to read (usually zero) * @param [in] data_length: Length of the data to read @@ -74,8 +74,8 @@ class UartPort { private: const static unsigned int kDefaultBufferSize = 1024; //!< Default buffer size - RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OnBoardComputer) - RingBuffer* tx_buffer_; //!< Transmit buffer (OnBoardComputer -> Component) + RingBuffer* rx_buffer_; //!< Receive buffer (Component -> OBC) + RingBuffer* tx_buffer_; //!< Transmit buffer (OBC-> Component) }; #endif // S2E_COMPONENTS_PORTS_UART_PORT_HPP_ diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index dce51b425..dd85e61a3 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -56,8 +56,8 @@ class OnBoardComputer : public Component { * @fn ConnectComPort * @brief Connect UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID - * @param [in] tx_buffer_size: TX (OnBoardComputer -> Component) buffer size - * @param [in] rx_buffer_size: RX (Component -> OnBoardComputer) buffer size + * @param [in] tx_buffer_size: TX (OBC-> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size * @return -1: error, 0: success */ virtual int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size); @@ -70,7 +70,7 @@ class OnBoardComputer : public Component { virtual int CloseComPort(int port_id); /** * @fn SendFromObc - * @brief Send data from OBC to Components with UART used by OnBoardComputer side. + * @brief Send data from OBC to Components with UART used ny OBC side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -101,7 +101,7 @@ class OnBoardComputer : public Component { virtual int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length); /** * @fn ReceivedByObc - * @brief Read data from component to OBC with UART used by OnBoardComputer side. + * @brief Read data from component to OBC with UART used ny OBC side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 715f74033..9f8b73b82 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -49,8 +49,8 @@ class ObcWithC2a : public OnBoardComputer { * @fn ConnectComPort * @brief Connect UART communication port between OnBoardComputer and a component * @param [in] port_id: Port ID - * @param [in] tx_buffer_size: TX (OnBoardComputer -> Component) buffer size - * @param [in] rx_buffer_size: RX (Component -> OnBoardComputer) buffer size + * @param [in] tx_buffer_size: TX (OBC-> Component) buffer size + * @param [in] rx_buffer_size: RX (Component -> OBC) buffer size * @return -1: error, 0: success */ int ConnectComPort(int port_id, int tx_buffer_size, int rx_buffer_size) override; @@ -63,7 +63,7 @@ class ObcWithC2a : public OnBoardComputer { int CloseComPort(int port_id) override; /** * @fn SendFromObc - * @brief Send data from OBC to Components with UART used by OnBoardComputer side. + * @brief Send data from OBC to Components with UART used ny OBC side. * @param [in] port_id: Port ID * @param [in] buffer: Send data buffer * @param [in] offset: Data offset for the buffer @@ -94,7 +94,7 @@ class ObcWithC2a : public OnBoardComputer { int SendFromCompo(int port_id, unsigned char* buffer, int offset, int length) override; /** * @fn ReceivedByObc - * @brief Read data from component to OBC with UART used by OnBoardComputer side. + * @brief Read data from component to OBC with UART used ny OBC side. * @param [in] port_id: Port ID * @param [out] buffer: Read data buffer * @param [in] offset: Data offset for the buffer From e175f53507839fd581c53b55d132c0d239a5242c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:14:40 +0100 Subject: [PATCH 0873/1086] fix public function name --- src/components/real/communication/antenna.cpp | 4 ++-- src/components/real/communication/antenna.hpp | 8 ++++---- .../real/communication/ground_station_calculator.cpp | 4 ++-- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 0ce58fb2c..cf009f37f 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -83,10 +83,10 @@ double Antenna::CalcAntennaGain(const AntennaParameters antenna_parameters, cons return gain_dBi; } -double Antenna::CalcTxEIRP_dBW(const double theta_rad, const double phi_rad) const { +double Antenna::CalcTxEirp_dBW(const double theta_rad, const double phi_rad) const { return tx_eirp_dBW_ + CalcAntennaGain(tx_parameters_, theta_rad, phi_rad); } -double Antenna::CalcRxGT_dB_K(const double theta_rad, const double phi_rad) const { +double Antenna::CalcRxGt_dB_K(const double theta_rad, const double phi_rad) const { return rx_gt_dBK_ + CalcAntennaGain(rx_parameters_, theta_rad, phi_rad); } diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index dc66d03a1..8620e8fc1 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -80,21 +80,21 @@ class Antenna { ~Antenna(); /** - * @fn CalcTxEIRP_dBW + * @fn CalcTxEirp_dBW * @brief Calculation of TX EIRP * @param [in] theta: Angle from PZ axis on the antenna frame [rad] * @param [in] phi: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return TX EIRP [dBW] */ - double CalcTxEIRP_dBW(const double theta_rad, const double phi_rad = 0.0) const; + double CalcTxEirp_dBW(const double theta_rad, const double phi_rad = 0.0) const; /** - * @fn CalcRxGT_dB_K + * @fn CalcRxGt_dB_K * @brief Calculation of RX G/T * @param [in] theta: Angle from PZ axis on the antenna frame [rad] * @param [in] phi: from PX axis on the antenna frame [rad] (Set zero for axial symmetry pattern) * @return RX G/T [dB/K] */ - double CalcRxGT_dB_K(const double theta_rad, const double phi_rad = 0.0) const; + double CalcRxGt_dB_K(const double theta_rad, const double phi_rad = 0.0) const; // Getter /** diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 834a08ec1..3ecdaa42a 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -89,9 +89,9 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); // Calc CN0 - double cn0_dBHz = spacecraft_tx_antenna.CalcTxEIRP_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + double cn0_dBHz = spacecraft_tx_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - ground_station_rx_antenna.CalcRxGT_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + ground_station_rx_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } From 95d383f590da7ec5fd93f3449a4b441ccf875282 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:15:24 +0100 Subject: [PATCH 0874/1086] fix public function name --- .../real/communication/ground_station_calculator.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index edc76a56e..cf8eee347 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -66,15 +66,15 @@ class GroundStationCalculator : public ILoggable { // Getter /** - * @fn GetMaxBitrate + * @fn GetMaxBitrate_Mbps * @brief Return max bitrate [Mbps] */ - inline double GetMaxBitrate() const { return max_bitrate_Mbps_; } + inline double GetMaxBitrate_Mbps() const { return max_bitrate_Mbps_; } /** - * @fn GetReceiveMargin + * @fn GetReceiveMargin_dB * @brief Return receive margin [dB] */ - inline double GetReceiveMargin() const { return receive_margin_dB_; } + inline double GetReceiveMargin_dB() const { return receive_margin_dB_; } // Setter /** From e6c48516f3cc4b6347711969500efa1ac729915c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:21:09 +0100 Subject: [PATCH 0875/1086] Fix comments --- src/disturbances/gravity_gradient.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 8480df75f..546e9511a 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -17,7 +17,7 @@ GravityGradient::GravityGradient(const double gravity_constant_m3_s2, const bool : SimpleDisturbance(is_calculation_enabled), gravity_constant_m3_s2_(gravity_constant_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - // TODO: use structure information to get rotor_inertia_kgm2 tensor + // TODO: use structure information to get inertia tensor CalcTorque_b_Nm(local_environment.GetCelestialInformation().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); } From 9201d9b8ae5168a4c3612a823e17bb94f294afb4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:22:09 +0100 Subject: [PATCH 0876/1086] Fix comments --- src/dynamics/attitude/attitude.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index ebb9af081..15b4d4beb 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -58,7 +58,7 @@ class Attitude : public ILoggable, public SimulationObject { inline double GetEnergy() const { return kinetic_energy_J_; } /** * @fn GetInertiaTensor - * @brief Return rotor_inertia_kgm2 tensor [kg m^2] + * @brief Return inertia tensor [kg m^2] */ inline libra::Matrix<3, 3> GetInertiaTensor() const { return inertia_tensor_kgm2_; } @@ -119,7 +119,7 @@ class Attitude : public ILoggable, public SimulationObject { libra::Vector<3> torque_b_Nm_; //!< Torque in the body fixed frame [Nm] libra::Matrix<3, 3> inertia_tensor_kgm2_; //!< Inertia tensor of the spacecraft [kg m^2] TODO: Move to Structure - libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the rotor_inertia_kgm2 tensor + libra::Matrix<3, 3> inv_inertia_tensor_; //!< Inverse matrix of the inertia tensor libra::Vector<3> angular_momentum_spacecraft_b_Nms_; //!< Angular momentum of spacecraft in the body fixed frame [Nms] libra::Vector<3> angular_momentum_reaction_wheel_b_Nms_; //!< Angular momentum of reaction wheel in the body fixed frame [Nms] From e2fb800472bcd18489a9dae8e94f42cbaeb267fa Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:23:12 +0100 Subject: [PATCH 0877/1086] Fix comments --- src/dynamics/attitude/attitude_rk4.hpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/dynamics/attitude/controlled_attitude.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index 94c5f4718..dc7bc2d54 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -19,7 +19,7 @@ class AttitudeRk4 : public Attitude { * @brief Constructor * @param [in] angular_velocity_b_rad_s: Initial value of spacecraft angular velocity of the body fixed frame [rad/s] * @param [in] quaternion_i2b: Initial value of attitude quaternion from the inertial frame to the body fixed frame - * @param [in] inertia_tensor_kgm2: Initial value of rotor_inertia_kgm2 tensor of the spacecraft [kg m^2] + * @param [in] inertia_tensor_kgm2: Initial value of inertia tensor of the spacecraft [kg m^2] * @param [in] torque_b_Nm: Initial torque acting on the spacecraft in the body fixed frame [Nm] * @param [in] propagation_step_s: Initial value of propagation step width [sec] * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 3fcbb1a8e..cc332ac54 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -20,7 +20,7 @@ ControlledAttitude::ControlledAttitude(const AttitudeControlMode main_mode, cons local_celestial_information_(local_celestial_information), orbit_(orbit) { quaternion_i2b_ = quaternion_i2b; - inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: rotor_inertia_kgm2 tensor should be initialized in the Attitude base class + inertia_tensor_kgm2_ = inertia_tensor_kgm2; // FIXME: inertia tensor should be initialized in the Attitude base class inv_inertia_tensor_ = CalcInverseMatrix(inertia_tensor_kgm2_); Initialize(); diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 278282ec9..52411f938 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -123,7 +123,7 @@ class ControlledAttitude : public Attitude { * @fn CalcTargetDirection_i * @brief Calculate target direction from attitude control mode * @param [in] mode: Attitude control mode - * @return Target direction at the rotor_inertia_kgm2 frame0 + * @return Target direction at the inertia frame */ libra::Vector<3> CalcTargetDirection_i(AttitudeControlMode mode); /** From e9578c375c74a19e0b924705fa92e12fccc37f36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:25:07 +0100 Subject: [PATCH 0878/1086] Fix comments --- src/simulation/hils/hils_port_manager.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index a8c5d1fe5..ebbade3b9 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -47,7 +47,7 @@ class HilsPortManager { virtual int UartCloseComPort(unsigned int port_id); /** * @fn UartReceive - * @brief UART data receive from COM port (ex. OnBoardComputer) to components in S2E + * @brief UART data receive from COM port (ex. OBC to components in S2E * @param [in] port_id: COM port ID * @param [out] buffer: Data buffer to receive * @param [in] offset: Start offset for the data buffer to receive @@ -56,7 +56,7 @@ class HilsPortManager { virtual int UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int count); /** * @fn UartSend - * @brief UART data send from components in S2E to COM port (ex. OnBoardComputer) + * @brief UART data send from components in S2E to COM port (ex. OBC) * @param [in] port_id: COM port ID * @param [in] buffer: Data buffer to send * @param [in] offset: Start offset for the data buffer to send From 373dd18f72d693eff316fcaeb06092d6ef9a8f2f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:26:01 +0100 Subject: [PATCH 0879/1086] Fix comments --- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 4f5b0d568..579e10a3a 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -16,7 +16,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // PCU power port connection pcu_ = new PowerControlUnit(clock_gen); - pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OnBoardComputer: assumed power consumption is defined here + pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyroSensor pcu_->ConnectPort(2, 1.0); // for other all components From c71aa22f00e9bf4199e6a100de094274be8435fc Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:35:47 +0100 Subject: [PATCH 0880/1086] Fix simulation config --- src/disturbances/disturbances.cpp | 4 +-- src/dynamics/dynamics.cpp | 6 ++-- src/environment/global/global_environment.cpp | 8 +++--- src/environment/local/local_environment.cpp | 2 +- src/simulation/case/simulation_case.cpp | 28 +++++++++++-------- .../ground_station/ground_station.cpp | 4 +-- .../sample_ground_station_components.cpp | 2 +- src/simulation/simulation_configuration.hpp | 18 +++++++----- .../sample_spacecraft/sample_components.cpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 4 +-- .../spacecraft/structure/structure.cpp | 2 +- 11 files changed, 45 insertions(+), 35 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index a9a7e3d2f..57d04754a 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -63,7 +63,7 @@ void Disturbances::LogSetup(Logger& logger) { void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* global_environment) { - IniAccess ini_access = IniAccess(sim_config->sat_file_[sat_id]); + IniAccess ini_access = IniAccess(sim_config->spacecraft_file_list_[sat_id]); initialize_file_name_ = ini_access.ReadString("SETTING_FILES", "disturbance_file"); GravityGradient* gg_dist = new GravityGradient( @@ -74,7 +74,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const InitSolarRadiationPressureDisturbance(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(srp_dist); - ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->ini_base_fname_)); + ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->initialize_base_file_name_)); acceleration_disturbances_list_.push_back(third_body_gravity); if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index afee0d594..5f435c33c 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -25,12 +25,12 @@ void Dynamics::Initialize(SimulationConfig* simulation_configuration, const Simu structure_ = structure; // Initialize - orbit_ = InitOrbit(&(local_celestial_information->GetGlobalInformation()), simulation_configuration->sat_file_[spacecraft_id], + orbit_ = InitOrbit(&(local_celestial_information->GetGlobalInformation()), simulation_configuration->spacecraft_file_list_[spacecraft_id], simulation_time->GetOrbitRkStepTime_s(), simulation_time->GetCurrentTime_jd(), local_celestial_information->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", relative_information); - attitude_ = InitAttitude(simulation_configuration->sat_file_[spacecraft_id], orbit_, local_celestial_information, + attitude_ = InitAttitude(simulation_configuration->spacecraft_file_list_[spacecraft_id], orbit_, local_celestial_information, simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor(), spacecraft_id); - temperature_ = InitTemperature(simulation_configuration->sat_file_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); + temperature_ = InitTemperature(simulation_configuration->spacecraft_file_list_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); // To get initial value orbit_->UpdateByAttitude(attitude_->GetQuaternion_i2b()); diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index ba264774d..fac66c5a0 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -20,13 +20,13 @@ GlobalEnvironment::~GlobalEnvironment() { void GlobalEnvironment::Initialize(SimulationConfig* simulation_configuration) { // Get ini file path - IniAccess iniAccess = IniAccess(simulation_configuration->ini_base_fname_); - std::string simulation_time_ini_path = simulation_configuration->ini_base_fname_; + IniAccess iniAccess = IniAccess(simulation_configuration->initialize_base_file_name_); + std::string simulation_time_ini_path = simulation_configuration->initialize_base_file_name_; // Initialize simulation_time_ = InitSimulationTime(simulation_time_ini_path); - celestial_information_ = InitCelestialInformation(simulation_configuration->ini_base_fname_); - hipparcos_catalogue_ = InitHipparcosCatalogue(simulation_configuration->ini_base_fname_); + celestial_information_ = InitCelestialInformation(simulation_configuration->initialize_base_file_name_); + hipparcos_catalogue_ = InitHipparcosCatalogue(simulation_configuration->initialize_base_file_name_); gnss_satellites_ = InitGnssSatellites(simulation_configuration->gnss_file_); // Calc initial value diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index b79741d1e..9699bb218 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -24,7 +24,7 @@ LocalEnvironment::~LocalEnvironment() { void LocalEnvironment::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { // Read file name - IniAccess iniAccess = IniAccess(simulation_configuration->sat_file_[spacecraft_id]); + IniAccess iniAccess = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); std::string ini_fname = iniAccess.ReadString("SETTING_FILES", "local_environment_file"); // Save ini file diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 684b079cb..d6a9b487a 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -12,27 +12,33 @@ SimulationCase::SimulationCase(std::string ini_base) { IniAccess simbase_ini = IniAccess(ini_base); const char* section = "SIMULATION_SETTINGS"; - sim_config_.ini_base_fname_ = ini_base; - sim_config_.main_logger_ = InitLog(sim_config_.ini_base_fname_); - sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); - sim_config_.gs_file_ = simbase_ini.ReadString(section, "ground_station_file"); - sim_config_.inter_sat_comm_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); + sim_config_.initialize_base_file_name_ = ini_base; + sim_config_.main_logger_ = InitLog(sim_config_.initialize_base_file_name_); + sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); + sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + + sim_config_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); + sim_config_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + + sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); glo_env_ = new GlobalEnvironment(&sim_config_); } SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); const char* section = "SIMULATION_SETTINGS"; - sim_config_.ini_base_fname_ = ini_base; + sim_config_.initialize_base_file_name_ = ini_base; // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(mc_sim.GetNumOfExecutionsDone()) + ".csv"; // ToDo: Consider that `enable_inilog = false` is fine or not? sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, mc_sim.LogHistory()); - sim_config_.num_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - sim_config_.sat_file_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); - sim_config_.gs_file_ = simbase_ini.ReadString(section, "ground_station_file"); - sim_config_.inter_sat_comm_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); + sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); + sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + + sim_config_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); + sim_config_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + + sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); // Global Environment glo_env_ = new GlobalEnvironment(&sim_config_); diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 31ec14617..808fe3327 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -15,7 +15,7 @@ GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id) { Initialize(gs_id_, config); - num_sc_ = config->num_of_simulated_spacecraft_; + num_sc_ = config->number_of_simulated_spacecraft_; for (int i = 0; i < num_sc_; i++) { is_visible_[i] = false; } @@ -24,7 +24,7 @@ GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id GroundStation::~GroundStation() {} void GroundStation::Initialize(int gs_id, SimulationConfig* config) { - std::string gs_ini_path = config->gs_file_; + std::string gs_ini_path = config->ground_station_file_list_[0]; auto conf = IniAccess(gs_ini_path); const char* section_base = "GROUND_STATION_"; diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index dc9898c1a..95c5ed8a1 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -7,7 +7,7 @@ #include SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { - IniAccess iniAccess = IniAccess(config_->gs_file_); + IniAccess iniAccess = IniAccess(config_->ground_station_file_list_[0]); std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); config_->main_logger_->CopyFileToLogDirectory(ant_ini_path); diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index 2e6aaf036..65cbe2ae3 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -16,13 +16,17 @@ * @brief Simulation setting information */ struct SimulationConfig { - std::string ini_base_fname_; //!< Base file name for initialization - Logger* main_logger_; //!< Main logger - int num_of_simulated_spacecraft_; //!< Number of simulated spacecraft - std::vector sat_file_; //!< File name list for spacecraft initialization - std::string gs_file_; //!< File name for ground station initialization - std::string inter_sat_comm_file_; //!< File name for inter-satellite communication initialization - std::string gnss_file_; //!< File name for GNSS initialization + std::string initialize_base_file_name_; //!< Base file name for initialization + Logger* main_logger_; //!< Main logger + + unsigned int number_of_simulated_spacecraft_; //!< Number of simulated spacecraft + std::vector spacecraft_file_list_; //!< File name list for spacecraft initialization + + unsigned int number_of_simulated_ground_station_; //!< Number of simulated spacecraft + std::vector ground_station_file_list_; //!< File name for ground station initialization + + std::string inter_sc_communication_file_; //!< File name for inter-satellite communication initialization + std::string gnss_file_; //!< File name for GNSS initialization /** * @fn ~SimulationConfig diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 579e10a3a..9bac764df 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -12,7 +12,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id) : config_(config), dynamics_(dynamics), structure_(structure), local_env_(local_environment), glo_env_(glo_env) { - IniAccess iniAccess = IniAccess(config_->sat_file_[sat_id]); + IniAccess iniAccess = IniAccess(config_->spacecraft_file_list_[sat_id]); // PCU power port connection pcu_ = new PowerControlUnit(clock_gen); diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 8aff1967e..b9c9299d5 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -35,7 +35,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); - sim_config->main_logger_->CopyFileToLogDirectory(sim_config->sat_file_[sat_id]); + sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); rel_info_ = nullptr; } @@ -47,7 +47,7 @@ void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironmen dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_, rel_info); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); - sim_config->main_logger_->CopyFileToLogDirectory(sim_config->sat_file_[sat_id]); + sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); rel_info_ = rel_info; rel_info_->RegisterDynamicsInfo(sat_id, dynamics_); diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 2b1b3f661..7d26fc817 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -17,7 +17,7 @@ Structure::~Structure() { void Structure::Initialize(SimulationConfig* sim_config, const int sat_id) { // Read file name - IniAccess conf = IniAccess(sim_config->sat_file_[sat_id]); + IniAccess conf = IniAccess(sim_config->spacecraft_file_list_[sat_id]); std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); // Save ini file sim_config->main_logger_->CopyFileToLogDirectory(ini_fname); From a0db89e55a62ce992f8d0ede46ece006da9d6d8e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:37:57 +0100 Subject: [PATCH 0881/1086] Fix private variables name --- .../sample_spacecraft/sample_components.cpp | 20 +++++----- .../sample_spacecraft/sample_components.hpp | 10 ++--- .../sample_spacecraft/sample_spacecraft.cpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 39 ++++++++++--------- src/simulation/spacecraft/spacecraft.hpp | 20 +++++----- 5 files changed, 47 insertions(+), 44 deletions(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 9bac764df..75c6f04be 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -11,7 +11,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id) - : config_(config), dynamics_(dynamics), structure_(structure), local_env_(local_environment), glo_env_(glo_env) { + : config_(config), dynamics_(dynamics), structure_(structure), local_environment_(local_environment), glo_env_(glo_env) { IniAccess iniAccess = IniAccess(config_->spacecraft_file_list_[sat_id]); // PCU power port connection @@ -33,20 +33,21 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Magnetometer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_sensor_ = new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, - glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); + mag_sensor_ = + new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + &(local_environment_->GetGeomagneticField()))); // StarSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - stt_ = new StarSensor( - InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_env_)); + stt_ = new StarSensor(InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + dynamics_, local_environment_)); // SunSensor ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_env_->GetSolarRadiationPressure()), - &(local_env_->GetCelestialInformation()))); + sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_environment_->GetSolarRadiationPressure()), + &(local_environment_->GetCelestialInformation()))); // GNSS-R ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); @@ -57,8 +58,9 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // Magnetorquer ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); config_->main_logger_->CopyFileToLogDirectory(ini_path); - mag_torquer_ = new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, - glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_env_->GetGeomagneticField()))); + mag_torquer_ = + new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + &(local_environment_->GetGeomagneticField()))); // RW ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 4b3bd9f04..2bb13f0ec 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -111,11 +111,11 @@ class SampleComponents : public InstalledComponents { */ // States - const SimulationConfig* config_; //!< Simulation settings - const Dynamics* dynamics_; //!< Dynamics information of the spacecraft - Structure* structure_; //!< Structure information of the spacecraft - const LocalEnvironment* local_env_; //!< Local environment information around the spacecraft - const GlobalEnvironment* glo_env_; //!< Global environment information + const SimulationConfig* config_; //!< Simulation settings + const Dynamics* dynamics_; //!< Dynamics information of the spacecraft + Structure* structure_; //!< Structure information of the spacecraft + const LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft + const GlobalEnvironment* glo_env_; //!< Global environment information }; #endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 5579b0508..1779ff913 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -11,6 +11,6 @@ #include "sample_components.hpp" SampleSat::SampleSat(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : Spacecraft(sim_config, glo_env, sat_id) { - sample_components_ = new SampleComponents(dynamics_, structure_, local_env_, glo_env, sim_config, &clock_gen_, sat_id); + sample_components_ = new SampleComponents(dynamics_, structure_, local_environment_, glo_env, sim_config, &clock_generator_, sat_id); components_ = sample_components_; } diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index b9c9299d5..91d355094 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -8,54 +8,55 @@ #include #include -Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : sat_id_(sat_id) { +Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : spacecraft_id_(sat_id) { Initialize(sim_config, glo_env, sat_id); } Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id) - : sat_id_(sat_id) { + : spacecraft_id_(sat_id) { Initialize(sim_config, glo_env, rel_info, sat_id); } Spacecraft::~Spacecraft() { - if (rel_info_ != nullptr) { - rel_info_->RemoveDynamicsInfo(sat_id_); + if (relative_information_ != nullptr) { + relative_information_->RemoveDynamicsInfo(spacecraft_id_); } delete structure_; delete dynamics_; - delete local_env_; + delete local_environment_; delete disturbances_; delete components_; } void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { - clock_gen_.ClearTimerCount(); + clock_generator_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); - local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_); + local_environment_ = new LocalEnvironment(sim_config, glo_env, sat_id); + dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), sat_id, structure_); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); - rel_info_ = nullptr; + relative_information_ = nullptr; } void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id) { - clock_gen_.ClearTimerCount(); + clock_generator_.ClearTimerCount(); structure_ = new Structure(sim_config, sat_id); - local_env_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_env_->GetCelestialInformation()), sat_id, structure_, rel_info); + local_environment_ = new LocalEnvironment(sim_config, glo_env, sat_id); + dynamics_ = + new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), sat_id, structure_, rel_info); disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); - rel_info_ = rel_info; - rel_info_->RegisterDynamicsInfo(sat_id, dynamics_); + relative_information_ = rel_info; + relative_information_->RegisterDynamicsInfo(sat_id, dynamics_); } void Spacecraft::LogSetup(Logger& logger) { dynamics_->LogSetup(logger); - local_env_->LogSetup(logger); + local_environment_->LogSetup(logger); disturbances_->LogSetup(logger); components_->LogSetup(logger); } @@ -64,11 +65,11 @@ void Spacecraft::Update(const SimulationTime* sim_time) { dynamics_->ClearForceTorque(); // Update local environment and disturbance - local_env_->Update(dynamics_, sim_time); - disturbances_->Update(*local_env_, *dynamics_, sim_time); + local_environment_->Update(dynamics_, sim_time); + disturbances_->Update(*local_environment_, *dynamics_, sim_time); // Update components - clock_gen_.UpdateComponents(sim_time); + clock_generator_.UpdateComponents(sim_time); // Add generated force and torque by disturbances dynamics_->AddAcceleration_i_m_s2(disturbances_->GetAcceleration_i_m_s2()); @@ -80,7 +81,7 @@ void Spacecraft::Update(const SimulationTime* sim_time) { dynamics_->AddForce_b_N(components_->GenerateForce_N_b()); // Propagate dynamics - dynamics_->Update(sim_time, &(local_env_->GetCelestialInformation())); + dynamics_->Update(sim_time, &(local_environment_->GetCelestialInformation())); } void Spacecraft::Clear(void) { dynamics_->ClearForceTorque(); } diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 0252ca8d6..9706c516f 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -82,7 +82,7 @@ class Spacecraft { * @fn GetlocalEnv * @brief Get local environment around the spacecraft */ - inline const LocalEnvironment& GetLocalEnv() const { return *local_env_; } + inline const LocalEnvironment& GetLocalEnv() const { return *local_environment_; } /** * @fn GetDisturbances * @brief Get disturbance acting of the spacecraft @@ -102,17 +102,17 @@ class Spacecraft { * @fn GetSatID * @brief Get ID of the spacecraft */ - inline int GetSatID() const { return sat_id_; } + inline int GetSatID() const { return spacecraft_id_; } protected: - ClockGenerator clock_gen_; //!< Origin of clock for the spacecraft - Dynamics* dynamics_; //!< Dynamics information of the spacecraft - RelativeInformation* rel_info_; //!< Relative information with respect to the other spacecraft - LocalEnvironment* local_env_; //!< Local environment information around the spacecraft - Disturbances* disturbances_; //!< Disturbance information acting on the spacecraft - Structure* structure_; //!< Structure information of the spacecraft - InstalledComponents* components_; //!< Components information installed on the spacecraft - const int sat_id_; //!< ID of the spacecraft + ClockGenerator clock_generator_; //!< Origin of clock for the spacecraft + Dynamics* dynamics_; //!< Dynamics information of the spacecraft + RelativeInformation* relative_information_; //!< Relative information with respect to the other spacecraft + LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft + Disturbances* disturbances_; //!< Disturbance information acting on the spacecraft + Structure* structure_; //!< Structure information of the spacecraft + InstalledComponents* components_; //!< Components information installed on the spacecraft + const unsigned int spacecraft_id_; //!< ID of the spacecraft }; #endif // S2E_SIMULATION_SPACECRAFT_SPACECRAFT_HPP_ From 7ac10f765af7ad098bbb6632ff2a236d5e7e188e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:39:48 +0100 Subject: [PATCH 0882/1086] Fix function variables --- src/disturbances/disturbances.cpp | 18 +- src/disturbances/disturbances.hpp | 17 +- src/environment/global/clock_generator.cpp | 4 +- src/environment/global/clock_generator.hpp | 4 +- src/environment/global/gnss_satellites.cpp | 413 +++++++++--------- src/environment/global/gnss_satellites.hpp | 78 ++-- src/simulation/case/sample_case.cpp | 6 +- .../inter_spacecraft_communication.cpp | 2 +- .../inter_spacecraft_communication.hpp | 2 +- .../relative_information.cpp | 8 +- .../relative_information.hpp | 8 +- .../sample_spacecraft/sample_components.cpp | 7 +- .../sample_spacecraft/sample_components.hpp | 4 +- .../sample_spacecraft/sample_spacecraft.cpp | 6 +- .../sample_spacecraft/sample_spacecraft.hpp | 2 +- src/simulation/spacecraft/spacecraft.cpp | 54 +-- src/simulation/spacecraft/spacecraft.hpp | 12 +- .../spacecraft/structure/structure.cpp | 8 +- .../spacecraft/structure/structure.hpp | 4 +- 19 files changed, 337 insertions(+), 320 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 57d04754a..8614b5d7c 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -15,8 +15,9 @@ #include "solar_radiation_pressure_disturbance.hpp" #include "third_body_gravity.hpp" -Disturbances::Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* glo_env) { - InitializeInstances(sim_config, sat_id, structure, glo_env); +Disturbances::Disturbances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, + const GlobalEnvironment* global_environment) { + InitializeInstances(simulation_configuration, spacecraft_id, structure, global_environment); InitializeForceAndTorque(); InitializeAcceleration(); } @@ -31,9 +32,9 @@ Disturbances::~Disturbances() { } } -void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* sim_time) { +void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* simulation_time) { // Update disturbances that depend on the attitude (and the position) - if (sim_time->GetAttitudePropagateFlag()) { + if (simulation_time->GetAttitudePropagateFlag()) { InitializeForceAndTorque(); for (auto dist : disturbances_list_) { dist->UpdateIfEnabled(local_environment, dynamics); @@ -42,7 +43,7 @@ void Disturbances::Update(const LocalEnvironment& local_environment, const Dynam } } // Update disturbances that depend only on the position - if (sim_time->GetOrbitPropagateFlag()) { + if (simulation_time->GetOrbitPropagateFlag()) { InitializeAcceleration(); for (auto acc_dist : acceleration_disturbances_list_) { acc_dist->UpdateIfEnabled(local_environment, dynamics); @@ -61,9 +62,9 @@ void Disturbances::LogSetup(Logger& logger) { logger.CopyFileToLogDirectory(initialize_file_name_); } -void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, +void Disturbances::InitializeInstances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment) { - IniAccess ini_access = IniAccess(sim_config->spacecraft_file_list_[sat_id]); + IniAccess ini_access = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); initialize_file_name_ = ini_access.ReadString("SETTING_FILES", "disturbance_file"); GravityGradient* gg_dist = new GravityGradient( @@ -74,7 +75,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* sim_config, const InitSolarRadiationPressureDisturbance(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); disturbances_list_.push_back(srp_dist); - ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, sim_config->initialize_base_file_name_)); + ThirdBodyGravity* third_body_gravity = + new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, simulation_configuration->initialize_base_file_name_)); acceleration_disturbances_list_.push_back(third_body_gravity); if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 06cd66741..d9c85bb61 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -24,12 +24,13 @@ class Disturbances { /** * @fn Disturbances * @brief Constructor - * @param [in] sim_config: Simulation Configuration - * @param [in] sat_id: Satellite ID + * @param [in] simulation_configuration: Simulation Configuration + * @param [in] spacecraft_id: Satellite ID * @param [in] structure: Structure information of spacecraft * @param [in] global_environment: Global environment information */ - Disturbances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, const GlobalEnvironment* global_environment); + Disturbances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, + const GlobalEnvironment* global_environment); /** * @fn ~Disturbances * @brief Destructor @@ -41,9 +42,9 @@ class Disturbances { * @brief Update all disturbance calculation * @param [in] local_environment: Local environment information * @param [in] dynamics: Dynamics information - * @param [in] sim_time: Simulation time + * @param [in] simulation_time: Simulation time */ - void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* sim_time); + void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* simulation_time); /** * @fn LogSetup * @brief log setup for all disturbances @@ -82,12 +83,12 @@ class Disturbances { /** * @fn InitializeInstances * @brief Initialize all disturbance class - * @param [in] sim_config: Simulation Configuration - * @param [in] sat_id: Satellite ID + * @param [in] simulation_configuration: Simulation Configuration + * @param [in] spacecraft_id: Satellite ID * @param [in] structure: Structure information of spacecraft * @param [in] global_environment: Global environment information */ - void InitializeInstances(const SimulationConfig* sim_config, const int sat_id, const Structure* structure, + void InitializeInstances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment); /** * @fn InitializeForceAndTorque diff --git a/src/environment/global/clock_generator.cpp b/src/environment/global/clock_generator.cpp index e5189a924..a196efac0 100644 --- a/src/environment/global/clock_generator.cpp +++ b/src/environment/global/clock_generator.cpp @@ -33,8 +33,8 @@ void ClockGenerator::TickToComponents() { timer_count_++; // TODO: Consider if "timer_count" is necessary } -void ClockGenerator::UpdateComponents(const SimulationTime* sim_time) { - if (sim_time->GetCompoUpdateFlag()) { +void ClockGenerator::UpdateComponents(const SimulationTime* simulation_time) { + if (simulation_time->GetCompoUpdateFlag()) { TickToComponents(); } } diff --git a/src/environment/global/clock_generator.hpp b/src/environment/global/clock_generator.hpp index 095350bcf..b09b80c4a 100644 --- a/src/environment/global/clock_generator.hpp +++ b/src/environment/global/clock_generator.hpp @@ -43,9 +43,9 @@ class ClockGenerator { /** * @fn UpdateComponents * @brief Execute TickToComponents when component update timing - * @param [in] sim_time: Simulation time + * @param [in] simulation_time: Simulation time */ - void UpdateComponents(const SimulationTime* sim_time); + void UpdateComponents(const SimulationTime* simulation_time); /** * @fn ClearTimerCount * @brief Clear time count diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index fe8213936..8037371f0 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -219,9 +219,9 @@ string GnssSat_coordinate::GetIDFromIndex(int index) const { int GnssSat_coordinate::GetNumOfSatellites() const { return all_sat_num_; } -bool GnssSat_coordinate::GetWhetherValid(int sat_id) const { - if (sat_id >= all_sat_num_) return false; - return validate_.at(sat_id); +bool GnssSat_coordinate::GetWhetherValid(int spacecraft_id) const { + if (spacecraft_id >= all_sat_num_) return false; + return validate_.at(spacecraft_id); } pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, UR_KINDS ur_flag) { @@ -313,7 +313,7 @@ pair GnssSat_position::Init(vector>& file, int in iss >> tmp; s.push_back(tmp); } - int sat_id = GetIndexFromID(s.front()); + int spacecraft_id = GetIndexFromID(s.front()); bool available_flag = true; libra::Vector<3> ecef_position_m(0.0); @@ -340,14 +340,14 @@ pair GnssSat_position::Init(vector>& file, int in eci_position(1) = sin_ * x + cos_ * y; eci_position(2) = z; - if (!unixtime_vector_.at(sat_id).empty() && std::abs(unix_time - unixtime_vector_.at(sat_id).back()) < 1.0) { - unixtime_vector_.at(sat_id).back() = unix_time; - gnss_sat_table_ecef_.at(sat_id).back() = ecef_position_m; - gnss_sat_table_eci_.at(sat_id).back() = eci_position; + if (!unixtime_vector_.at(spacecraft_id).empty() && std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1.0) { + unixtime_vector_.at(spacecraft_id).back() = unix_time; + gnss_sat_table_ecef_.at(spacecraft_id).back() = ecef_position_m; + gnss_sat_table_eci_.at(spacecraft_id).back() = eci_position; } else { - unixtime_vector_.at(sat_id).emplace_back(unix_time); - gnss_sat_table_ecef_.at(sat_id).emplace_back(ecef_position_m); - gnss_sat_table_eci_.at(sat_id).emplace_back(eci_position); + unixtime_vector_.at(spacecraft_id).emplace_back(unix_time); + gnss_sat_table_ecef_.at(spacecraft_id).emplace_back(ecef_position_m); + gnss_sat_table_eci_.at(spacecraft_id).emplace_back(eci_position); } } } @@ -369,137 +369,137 @@ void GnssSat_position::SetUp(const double start_unix_time, const double step_sec ecef_.resize(all_sat_num_); eci_.resize(all_sat_num_); - for (int sat_id = 0; sat_id < all_sat_num_; ++sat_id) { - if (unixtime_vector_.at(sat_id).empty()) { - validate_.at(sat_id) = false; + for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { + if (unixtime_vector_.at(spacecraft_id).empty()) { + validate_.at(spacecraft_id) = false; continue; } - int index = - lower_bound(unixtime_vector_.at(sat_id).begin(), unixtime_vector_.at(sat_id).end(), start_unix_time) - unixtime_vector_.at(sat_id).begin(); - if (index == (int)unixtime_vector_.at(sat_id).size()) { - nearest_index_.at(sat_id) = index; - validate_.at(sat_id) = false; + int index = lower_bound(unixtime_vector_.at(spacecraft_id).begin(), unixtime_vector_.at(spacecraft_id).end(), start_unix_time) - + unixtime_vector_.at(spacecraft_id).begin(); + if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { + nearest_index_.at(spacecraft_id) = index; + validate_.at(spacecraft_id) = false; continue; } - double nearest_unixtime = unixtime_vector_.at(sat_id).at(index); + double nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); if (interpolation_number_ % 2 && index != 0) { - double pre_time = unixtime_vector_.at(sat_id).at(index - 1); + double pre_time = unixtime_vector_.at(spacecraft_id).at(index - 1); if (std::abs(start_unix_time - pre_time) < std::abs(start_unix_time - nearest_unixtime)) --index; } - nearest_index_.at(sat_id) = index; - nearest_unixtime = unixtime_vector_.at(sat_id).at(index); + nearest_index_.at(spacecraft_id) = index; + nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); if (std::abs(start_unix_time - nearest_unixtime) > time_interval_) { - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(sat_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; - time_period_.at(sat_id).push_back(unixtime_vector_.at(sat_id).at(now_index)); - ecef_.at(sat_id).push_back(gnss_sat_table_ecef_.at(sat_id).at(now_index)); - eci_.at(sat_id).push_back(gnss_sat_table_eci_.at(sat_id).at(now_index)); + time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); + ecef_.at(spacecraft_id).push_back(gnss_sat_table_ecef_.at(spacecraft_id).at(now_index)); + eci_.at(spacecraft_id).push_back(gnss_sat_table_eci_.at(spacecraft_id).at(now_index)); } - if ((int)time_period_.at(sat_id).size() != interpolation_number_) { - validate_.at(sat_id) = false; + if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { + validate_.at(spacecraft_id) = false; continue; } - double time_period_length = time_period_.at(sat_id).back() - time_period_.at(sat_id).front(); + double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1 + 3) + 1e-4) { // allow for 3 missing - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } else { - validate_.at(sat_id) = true; + validate_.at(spacecraft_id) = true; } if (std::abs(start_unix_time - nearest_unixtime) < 1e-4) { // for the numerical error, plus 1e-4 - gnss_sat_ecef_.at(sat_id) = gnss_sat_table_ecef_.at(sat_id).at(index); - gnss_sat_eci_.at(sat_id) = gnss_sat_table_eci_.at(sat_id).at(index); + gnss_sat_ecef_.at(spacecraft_id) = gnss_sat_table_ecef_.at(spacecraft_id).at(index); + gnss_sat_eci_.at(spacecraft_id) = gnss_sat_table_eci_.at(spacecraft_id).at(index); } else { - gnss_sat_ecef_.at(sat_id) = TrigonometricInterpolation(time_period_.at(sat_id), ecef_.at(sat_id), start_unix_time); - gnss_sat_eci_.at(sat_id) = TrigonometricInterpolation(time_period_.at(sat_id), eci_.at(sat_id), start_unix_time); + gnss_sat_ecef_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), ecef_.at(spacecraft_id), start_unix_time); + gnss_sat_eci_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), eci_.at(spacecraft_id), start_unix_time); } } } void GnssSat_position::Update(const double now_unix_time) { - for (int sat_id = 0; sat_id < all_sat_num_; ++sat_id) { - if (unixtime_vector_.at(sat_id).empty()) { - validate_.at(sat_id) = false; + for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { + if (unixtime_vector_.at(spacecraft_id).empty()) { + validate_.at(spacecraft_id) = false; continue; } - int index = nearest_index_.at(sat_id); - if (index == (int)unixtime_vector_.at(sat_id).size()) { - validate_.at(sat_id) = false; + int index = nearest_index_.at(spacecraft_id); + if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { + validate_.at(spacecraft_id) = false; continue; } - if (index + 1 < (int)unixtime_vector_.at(sat_id).size()) { - double pre_unix = unixtime_vector_.at(sat_id).at(index); - double post_unix = unixtime_vector_.at(sat_id).at(index + 1); + if (index + 1 < (int)unixtime_vector_.at(spacecraft_id).size()) { + double pre_unix = unixtime_vector_.at(spacecraft_id).at(index); + double post_unix = unixtime_vector_.at(spacecraft_id).at(index + 1); if (std::abs(now_unix_time - post_unix) < std::abs(now_unix_time - pre_unix)) { ++index; - nearest_index_.at(sat_id) = index; + nearest_index_.at(spacecraft_id) = index; - time_period_.at(sat_id).clear(); - ecef_.at(sat_id).clear(); - eci_.at(sat_id).clear(); + time_period_.at(spacecraft_id).clear(); + ecef_.at(spacecraft_id).clear(); + eci_.at(spacecraft_id).clear(); // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(sat_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; - time_period_.at(sat_id).push_back(unixtime_vector_.at(sat_id).at(now_index)); - ecef_.at(sat_id).push_back(gnss_sat_table_ecef_.at(sat_id).at(now_index)); - eci_.at(sat_id).push_back(gnss_sat_table_eci_.at(sat_id).at(now_index)); + time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); + ecef_.at(spacecraft_id).push_back(gnss_sat_table_ecef_.at(spacecraft_id).at(now_index)); + eci_.at(spacecraft_id).push_back(gnss_sat_table_eci_.at(spacecraft_id).at(now_index)); } } } - double nearest_unix_time = unixtime_vector_.at(sat_id).at(index); + double nearest_unix_time = unixtime_vector_.at(spacecraft_id).at(index); if (std::abs(now_unix_time - nearest_unix_time) > time_interval_) { - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } - if ((int)time_period_.at(sat_id).size() != interpolation_number_) { - validate_.at(sat_id) = false; + if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { + validate_.at(spacecraft_id) = false; continue; } - double time_period_length = time_period_.at(sat_id).back() - time_period_.at(sat_id).front(); + double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1 + 3) + 1e-4) { // allow for 3 missing - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } else { - validate_.at(sat_id) = true; + validate_.at(spacecraft_id) = true; } if (std::abs(now_unix_time - nearest_unix_time) < 1e-4) { // for the numerical error, plus 1e-4 - gnss_sat_ecef_.at(sat_id) = gnss_sat_table_ecef_.at(sat_id).at(index); - gnss_sat_eci_.at(sat_id) = gnss_sat_table_eci_.at(sat_id).at(index); + gnss_sat_ecef_.at(spacecraft_id) = gnss_sat_table_ecef_.at(spacecraft_id).at(index); + gnss_sat_eci_.at(spacecraft_id) = gnss_sat_table_eci_.at(spacecraft_id).at(index); } else { - gnss_sat_ecef_.at(sat_id) = TrigonometricInterpolation(time_period_.at(sat_id), ecef_.at(sat_id), now_unix_time); - gnss_sat_eci_.at(sat_id) = TrigonometricInterpolation(time_period_.at(sat_id), eci_.at(sat_id), now_unix_time); + gnss_sat_ecef_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), ecef_.at(spacecraft_id), now_unix_time); + gnss_sat_eci_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), eci_.at(spacecraft_id), now_unix_time); } } } -libra::Vector<3> GnssSat_position::GetSatEcef(int sat_id) const { - if (sat_id >= all_sat_num_) return libra::Vector<3>(0.0); - return gnss_sat_ecef_.at(sat_id); +libra::Vector<3> GnssSat_position::GetSatEcef(int spacecraft_id) const { + if (spacecraft_id >= all_sat_num_) return libra::Vector<3>(0.0); + return gnss_sat_ecef_.at(spacecraft_id); } -libra::Vector<3> GnssSat_position::GetSatEci(int sat_id) const { - if (sat_id >= all_sat_num_) return libra::Vector<3>(0.0); - return gnss_sat_eci_.at(sat_id); +libra::Vector<3> GnssSat_position::GetSatEci(int spacecraft_id) const { + if (spacecraft_id >= all_sat_num_) return libra::Vector<3>(0.0); + return gnss_sat_eci_.at(spacecraft_id); } void GnssSat_clock::Init(vector>& file, string file_extension, int interpolation_number, UR_KINDS ur_flag, @@ -573,19 +573,19 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in iss >> tmp; s.push_back(tmp); } - int sat_id = GetIndexFromID(s.front()); + int spacecraft_id = GetIndexFromID(s.front()); double clock = stod(s.at(4)); if (std::abs(clock - nan99) < 1.0) continue; // in the file, clock bias is expressed in [micro second], so by multiplying by the speed_of_light & 1e-6, they are converted to [m] clock *= (environment::speed_of_light_m_s * 1e-6); - if (!unixtime_vector_.at(sat_id).empty() && std::abs(unix_time - unixtime_vector_.at(sat_id).back()) < 1.0) { - unixtime_vector_.at(sat_id).back() = unix_time; - gnss_sat_clock_table_.at(sat_id).back() = clock; + if (!unixtime_vector_.at(spacecraft_id).empty() && std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1.0) { + unixtime_vector_.at(spacecraft_id).back() = unix_time; + gnss_sat_clock_table_.at(spacecraft_id).back() = clock; } else { - unixtime_vector_.at(sat_id).push_back(unix_time); - gnss_sat_clock_table_.at(sat_id).emplace_back(clock); + unixtime_vector_.at(spacecraft_id).push_back(unix_time); + gnss_sat_clock_table_.at(spacecraft_id).emplace_back(clock); } } } @@ -633,17 +633,19 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in std::free(time_tm); - int sat_id = GetIndexFromID(s.at(1)); + int spacecraft_id = GetIndexFromID(s.at(1)); double clock_bias = stod(s.at(9)) * environment::speed_of_light_m_s; // [s] -> [m] if (start_unix_time - unix_time > 1e-4) continue; // for the numerical error if (end_unix_time - unix_time < 1e-4) break; - if (!unixtime_vector_.at(sat_id).empty() && std::abs(unix_time - unixtime_vector_.at(sat_id).back()) < 1e-4) { // for the numerical error - unixtime_vector_.at(sat_id).back() = unix_time; - gnss_sat_clock_table_.at(sat_id).back() = clock_bias; + if (!unixtime_vector_.at(spacecraft_id).empty() && + std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1e-4) { // for the numerical error + unixtime_vector_.at(spacecraft_id).back() = unix_time; + gnss_sat_clock_table_.at(spacecraft_id).back() = clock_bias; } else { - if (!unixtime_vector_.at(sat_id).empty()) time_interval_ = min(time_interval_, unix_time - unixtime_vector_.at(sat_id).back()); - unixtime_vector_.at(sat_id).emplace_back(unix_time); - gnss_sat_clock_table_.at(sat_id).emplace_back(clock_bias); + if (!unixtime_vector_.at(spacecraft_id).empty()) + time_interval_ = min(time_interval_, unix_time - unixtime_vector_.at(spacecraft_id).back()); + unixtime_vector_.at(spacecraft_id).emplace_back(unix_time); + gnss_sat_clock_table_.at(spacecraft_id).emplace_back(clock_bias); } } } @@ -661,126 +663,126 @@ void GnssSat_clock::SetUp(const double start_unix_time, const double step_sec) { clock_bias_.resize(all_sat_num_); - for (int sat_id = 0; sat_id < all_sat_num_; ++sat_id) { - if (unixtime_vector_.at(sat_id).empty()) { - validate_.at(sat_id) = false; + for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { + if (unixtime_vector_.at(spacecraft_id).empty()) { + validate_.at(spacecraft_id) = false; continue; } - int index = - lower_bound(unixtime_vector_.at(sat_id).begin(), unixtime_vector_.at(sat_id).end(), start_unix_time) - unixtime_vector_.at(sat_id).begin(); - if (index == (int)unixtime_vector_.at(sat_id).size()) { - validate_.at(sat_id) = false; - nearest_index_.at(sat_id) = index; + int index = lower_bound(unixtime_vector_.at(spacecraft_id).begin(), unixtime_vector_.at(spacecraft_id).end(), start_unix_time) - + unixtime_vector_.at(spacecraft_id).begin(); + if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { + validate_.at(spacecraft_id) = false; + nearest_index_.at(spacecraft_id) = index; continue; } - double nearest_unixtime = unixtime_vector_.at(sat_id).at(index); + double nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); if (interpolation_number_ % 2 && index != 0) { - double pre_time = unixtime_vector_.at(sat_id).at(index - 1); + double pre_time = unixtime_vector_.at(spacecraft_id).at(index - 1); if (std::abs(start_unix_time - pre_time) < std::abs(start_unix_time - nearest_unixtime)) --index; } - nearest_index_.at(sat_id) = index; - nearest_unixtime = unixtime_vector_.at(sat_id).at(index); + nearest_index_.at(spacecraft_id) = index; + nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); if (std::abs(start_unix_time - nearest_unixtime) > time_interval_) { - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(sat_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; - time_period_.at(sat_id).push_back(unixtime_vector_.at(sat_id).at(now_index)); - clock_bias_.at(sat_id).push_back(gnss_sat_clock_table_.at(sat_id).at(now_index)); + time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); + clock_bias_.at(spacecraft_id).push_back(gnss_sat_clock_table_.at(spacecraft_id).at(now_index)); } - if ((int)time_period_.at(sat_id).size() != interpolation_number_) { - validate_.at(sat_id) = false; + if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { + validate_.at(spacecraft_id) = false; continue; } - double time_period_length = time_period_.at(sat_id).back() - time_period_.at(sat_id).front(); + double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1) + 1e-4) { // more strict for clock_bias - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } else { - validate_.at(sat_id) = true; + validate_.at(spacecraft_id) = true; } if (std::abs(start_unix_time - nearest_unixtime) < 1e-4) { // for the numerical error - gnss_sat_clock_.at(sat_id) = gnss_sat_clock_table_.at(sat_id).at(index); + gnss_sat_clock_.at(spacecraft_id) = gnss_sat_clock_table_.at(spacecraft_id).at(index); } else { - gnss_sat_clock_.at(sat_id) = LagrangeInterpolation(time_period_.at(sat_id), clock_bias_.at(sat_id), start_unix_time); + gnss_sat_clock_.at(spacecraft_id) = LagrangeInterpolation(time_period_.at(spacecraft_id), clock_bias_.at(spacecraft_id), start_unix_time); } } } void GnssSat_clock::Update(const double now_unix_time) { - for (int sat_id = 0; sat_id < all_sat_num_; ++sat_id) { - if (unixtime_vector_.at(sat_id).empty()) { - validate_.at(sat_id) = false; + for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { + if (unixtime_vector_.at(spacecraft_id).empty()) { + validate_.at(spacecraft_id) = false; continue; } - int index = nearest_index_.at(sat_id); - if (index == (int)unixtime_vector_.at(sat_id).size()) { - validate_.at(sat_id) = false; + int index = nearest_index_.at(spacecraft_id); + if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { + validate_.at(spacecraft_id) = false; continue; } - if (index + 1 < (int)unixtime_vector_.at(sat_id).size()) { - double pre_unix = unixtime_vector_.at(sat_id).at(index); - double post_unix = unixtime_vector_.at(sat_id).at(index + 1); + if (index + 1 < (int)unixtime_vector_.at(spacecraft_id).size()) { + double pre_unix = unixtime_vector_.at(spacecraft_id).at(index); + double post_unix = unixtime_vector_.at(spacecraft_id).at(index + 1); if (std::abs(now_unix_time - post_unix) < std::abs(now_unix_time - pre_unix)) { ++index; - nearest_index_.at(sat_id) = index; + nearest_index_.at(spacecraft_id) = index; - time_period_.at(sat_id).clear(); - clock_bias_.at(sat_id).clear(); + time_period_.at(spacecraft_id).clear(); + clock_bias_.at(spacecraft_id).clear(); // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(sat_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; - time_period_.at(sat_id).push_back(unixtime_vector_.at(sat_id).at(now_index)); - clock_bias_.at(sat_id).push_back(gnss_sat_clock_table_.at(sat_id).at(now_index)); + time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); + clock_bias_.at(spacecraft_id).push_back(gnss_sat_clock_table_.at(spacecraft_id).at(now_index)); } } } - if ((int)time_period_.at(sat_id).size() != interpolation_number_) { - validate_.at(sat_id) = false; + if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { + validate_.at(spacecraft_id) = false; continue; } - double nearest_unix_time = unixtime_vector_.at(sat_id).at(index); + double nearest_unix_time = unixtime_vector_.at(spacecraft_id).at(index); if (std::abs(now_unix_time - nearest_unix_time) > time_interval_) { - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } // in clock_bias, more strict. - double time_period_length = time_period_.at(sat_id).back() - time_period_.at(sat_id).front(); + double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1) + 1e-4) { // more strict for clock_bias - validate_.at(sat_id) = false; + validate_.at(spacecraft_id) = false; continue; } else { - validate_.at(sat_id) = true; + validate_.at(spacecraft_id) = true; } if (std::abs(now_unix_time - nearest_unix_time) < 1e-4) { - gnss_sat_clock_.at(sat_id) = gnss_sat_clock_table_.at(sat_id).at(index); + gnss_sat_clock_.at(spacecraft_id) = gnss_sat_clock_table_.at(spacecraft_id).at(index); } else { - gnss_sat_clock_.at(sat_id) = LagrangeInterpolation(time_period_.at(sat_id), clock_bias_.at(sat_id), now_unix_time); + gnss_sat_clock_.at(spacecraft_id) = LagrangeInterpolation(time_period_.at(spacecraft_id), clock_bias_.at(spacecraft_id), now_unix_time); } } } -double GnssSat_clock::GetSatClock(int sat_id) const { - if (sat_id >= all_sat_num_) return 0.0; - return gnss_sat_clock_.at(sat_id); +double GnssSat_clock::GetSatClock(int spacecraft_id) const { + if (spacecraft_id >= all_sat_num_) return 0.0; + return gnss_sat_clock_.at(spacecraft_id); } GnssSat_Info::GnssSat_Info() {} @@ -810,8 +812,8 @@ int GnssSat_Info::GetNumOfSatellites() const { } } -bool GnssSat_Info::GetWhetherValid(int sat_id) const { - if (position_.GetWhetherValid(sat_id) && clock_.GetWhetherValid(sat_id)) return true; +bool GnssSat_Info::GetWhetherValid(int spacecraft_id) const { + if (position_.GetWhetherValid(spacecraft_id) && clock_.GetWhetherValid(spacecraft_id)) return true; return false; } @@ -819,11 +821,11 @@ const GnssSat_position& GnssSat_Info::GetGnssSatPos() const { return position_; const GnssSat_clock& GnssSat_Info::GetGnssSatClock() const { return clock_; } -libra::Vector<3> GnssSat_Info::GetSatellitePositionEcef(int sat_id) const { return position_.GetSatEcef(sat_id); } +libra::Vector<3> GnssSat_Info::GetSatellitePositionEcef(int spacecraft_id) const { return position_.GetSatEcef(spacecraft_id); } -libra::Vector<3> GnssSat_Info::GetSatellitePositionEci(int sat_id) const { return position_.GetSatEci(sat_id); } +libra::Vector<3> GnssSat_Info::GetSatellitePositionEci(int spacecraft_id) const { return position_.GetSatEci(spacecraft_id); } -double GnssSat_Info::GetSatelliteClock(int sat_id) const { return clock_.GetSatClock(sat_id); } +double GnssSat_Info::GetSatelliteClock(int spacecraft_id) const { return clock_.GetSatClock(spacecraft_id); } GnssSatellites::GnssSatellites(bool is_calc_enabled) #ifdef GNSS_SATELLITES_DEBUG_OUTPUT @@ -860,31 +862,31 @@ void GnssSatellites::Init(vector>& true_position_file, int true_p return; } -void GnssSatellites::SetUp(const SimulationTime* sim_time) { +void GnssSatellites::SetUp(const SimulationTime* simulation_time) { if (!IsCalcEnabled()) return; tm* start_tm = initilized_tm(); - start_tm->tm_year = sim_time->GetStartYear() - 1900; - start_tm->tm_mon = sim_time->GetStartMonth() - 1; - start_tm->tm_mday = sim_time->GetStartDay(); - start_tm->tm_hour = sim_time->GetStartHour(); - start_tm->tm_min = sim_time->GetStartMinute(); - double start_sec = sim_time->GetStartSecond(); + start_tm->tm_year = simulation_time->GetStartYear() - 1900; + start_tm->tm_mon = simulation_time->GetStartMonth() - 1; + start_tm->tm_mday = simulation_time->GetStartDay(); + start_tm->tm_hour = simulation_time->GetStartHour(); + start_tm->tm_min = simulation_time->GetStartMinute(); + double start_sec = simulation_time->GetStartSecond(); start_tm->tm_sec = (int)start_sec; double unix_time = (double)mktime(start_tm) + start_sec - floor(start_sec); std::free(start_tm); - true_info_.SetUp(unix_time, sim_time->GetSimulationStep_s()); - estimate_info_.SetUp(unix_time, sim_time->GetSimulationStep_s()); + true_info_.SetUp(unix_time, simulation_time->GetSimulationStep_s()); + estimate_info_.SetUp(unix_time, simulation_time->GetSimulationStep_s()); start_unix_time_ = unix_time; return; } -void GnssSatellites::Update(const SimulationTime* sim_time) { +void GnssSatellites::Update(const SimulationTime* simulation_time) { if (!IsCalcEnabled()) return; - double elapsed_sec = sim_time->GetElapsedTime_s(); + double elapsed_sec = simulation_time->GetElapsedTime_s(); true_info_.Update(elapsed_sec + start_unix_time_); estimate_info_.Update(elapsed_sec + start_unix_time_); @@ -902,10 +904,10 @@ string GnssSatellites::GetIDFromIndex(int index) const { return estimate_info_.G int GnssSatellites::GetIndexFromID(string sat_num) const { return estimate_info_.GetGnssSatPos().GetIndexFromID(sat_num); } -bool GnssSatellites::GetWhetherValid(int sat_id) const { - if (sat_id >= GetNumOfSatellites()) return false; +bool GnssSatellites::GetWhetherValid(int spacecraft_id) const { + if (spacecraft_id >= GetNumOfSatellites()) return false; - if (true_info_.GetWhetherValid(sat_id) && estimate_info_.GetWhetherValid(sat_id)) + if (true_info_.GetWhetherValid(spacecraft_id) && estimate_info_.GetWhetherValid(spacecraft_id)) return true; else return false; @@ -917,95 +919,95 @@ const GnssSat_Info& GnssSatellites::Get_true_info() const { return true_info_; } const GnssSat_Info& GnssSatellites::Get_estimate_info() const { return estimate_info_; } -libra::Vector<3> GnssSatellites::GetSatellitePositionEcef(const int sat_id) const { - // sat_id is wrong or not valid - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) { +libra::Vector<3> GnssSatellites::GetSatellitePositionEcef(const int spacecraft_id) const { + // spacecraft_id is wrong or not valid + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { libra::Vector<3> res(0); return res; } - return estimate_info_.GetSatellitePositionEcef(sat_id); + return estimate_info_.GetSatellitePositionEcef(spacecraft_id); } -libra::Vector<3> GnssSatellites::GetSatellitePositionEci(const int sat_id) const { - // sat_id is wrong or not valid - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) { +libra::Vector<3> GnssSatellites::GetSatellitePositionEci(const int spacecraft_id) const { + // spacecraft_id is wrong or not valid + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { libra::Vector<3> res(0); return res; } - return estimate_info_.GetSatellitePositionEci(sat_id); + return estimate_info_.GetSatellitePositionEci(spacecraft_id); } -double GnssSatellites::GetSatelliteClock(const int sat_id) const { - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) { +double GnssSatellites::GetSatelliteClock(const int spacecraft_id) const { + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { return 0.0; } - return estimate_info_.GetSatelliteClock(sat_id); + return estimate_info_.GetSatelliteClock(spacecraft_id); } -double GnssSatellites::GetPseudoRangeECEF(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // sat_id is wrong or not validate - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return 0.0; +double GnssSatellites::GetPseudoRangeECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { + // spacecraft_id is wrong or not validate + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEcef(sat_id); + auto gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(sat_id); + res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(sat_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECEF); res += ionospheric_delay; return res; } -double GnssSatellites::GetPseudoRangeECI(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // sat_id is wrong or not validate - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return 0.0; +double GnssSatellites::GetPseudoRangeECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { + // spacecraft_id is wrong or not validate + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEci(sat_id); + auto gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(sat_id); + res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(sat_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECI); res += ionospheric_delay; return res; } -pair GnssSatellites::GetCarrierPhaseECEF(const int sat_id, libra::Vector<3> rec_position, double rec_clock, +pair GnssSatellites::GetCarrierPhaseECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // sat_id is wrong or not validate - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return {0.0, 0.0}; + // spacecraft_id is wrong or not validate + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return {0.0, 0.0}; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEcef(sat_id); + auto gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(sat_id); + res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(sat_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECEF); res -= ionospheric_delay; @@ -1019,23 +1021,23 @@ pair GnssSatellites::GetCarrierPhaseECEF(const int sat_id, libra return {cycle, bias}; } -pair GnssSatellites::GetCarrierPhaseECI(const int sat_id, libra::Vector<3> rec_position, double rec_clock, +pair GnssSatellites::GetCarrierPhaseECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // sat_id is wrong or not validate - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return {0.0, 0.0}; + // spacecraft_id is wrong or not validate + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return {0.0, 0.0}; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEci(sat_id); + auto gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(sat_id); + res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(sat_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECI); res -= ionospheric_delay; @@ -1050,9 +1052,10 @@ pair GnssSatellites::GetCarrierPhaseECI(const int sat_id, libra: } // for Ionospheric delay I[m] -double GnssSatellites::AddIonosphericDelay(const int sat_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const { - // sat_id is wrong or not validate - if (sat_id >= GetNumOfSatellites() || !GetWhetherValid(sat_id)) return 0.0; +double GnssSatellites::AddIonosphericDelay(const int spacecraft_id, const libra::Vector<3> rec_position, const double frequency, + const bool flag) const { + // spacecraft_id is wrong or not validate + if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; const double Earth_hemisphere = 6378.1; //[km] FIXME: Use constants.hpp @@ -1064,9 +1067,9 @@ double GnssSatellites::AddIonosphericDelay(const int sat_id, const libra::Vector libra::Vector<3> gnss_position; if (flag == ECEF) - gnss_position = true_info_.GetSatellitePositionEcef(sat_id); + gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); else if (flag == ECI) - gnss_position = true_info_.GetSatellitePositionEci(sat_id); + gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); double angle_rad = CalcAngleTwoVectors_rad(rec_position, gnss_position - rec_position); const double default_delay = 20.0; //[m] default delay @@ -1093,13 +1096,13 @@ std::string GnssSatellites::GetLogValue() const { void GnssSatellites::DebugOutput() { #ifdef GNSS_SATELLITES_DEBUG_OUTPUT - for (int sat_id = 0; sat_id < gps_sat_num_; ++sat_id) { - if (true_info_.GetWhetherValid(sat_id)) { - auto true_pos = true_info_.GetSatellitePositionEcef(sat_id); + for (int spacecraft_id = 0; spacecraft_id < gps_sat_num_; ++spacecraft_id) { + if (true_info_.GetWhetherValid(spacecraft_id)) { + auto true_pos = true_info_.GetSatellitePositionEcef(spacecraft_id); for (int i = 0; i < 3; ++i) { ofs_true << fixed << setprecision(10) << true_pos[i] << ","; } - auto true_clock = true_info_.GetSatelliteClock(sat_id); + auto true_clock = true_info_.GetSatelliteClock(spacecraft_id); ofs_true << true_clock << ","; } else { for (int i = 0; i < 4; ++i) { @@ -1107,12 +1110,12 @@ void GnssSatellites::DebugOutput() { } } - if (estimate_info_.GetWhetherValid(sat_id)) { - auto esti_pos = estimate_info_.GetSatellitePositionEcef(sat_id); + if (estimate_info_.GetWhetherValid(spacecraft_id)) { + auto esti_pos = estimate_info_.GetSatellitePositionEcef(spacecraft_id); for (int i = 0; i < 3; ++i) { ofs_esti << fixed << setprecision(10) << esti_pos[i] << ","; } - auto esti_clock = estimate_info_.GetSatelliteClock(sat_id); + auto esti_clock = estimate_info_.GetSatelliteClock(spacecraft_id); ofs_esti << esti_clock << ","; } else { for (int i = 0; i < 4; ++i) { @@ -1120,11 +1123,11 @@ void GnssSatellites::DebugOutput() { } } - if (GetWhetherValid(sat_id)) { - auto true_pos = true_info_.GetSatellitePositionEcef(sat_id); - auto true_clock = true_info_.GetSatelliteClock(sat_id); - auto esti_pos = estimate_info_.GetSatellitePositionEcef(sat_id); - auto esti_clock = estimate_info_.GetSatelliteClock(sat_id); + if (GetWhetherValid(spacecraft_id)) { + auto true_pos = true_info_.GetSatellitePositionEcef(spacecraft_id); + auto true_clock = true_info_.GetSatelliteClock(spacecraft_id); + auto esti_pos = estimate_info_.GetSatellitePositionEcef(spacecraft_id); + auto esti_clock = estimate_info_.GetSatelliteClock(spacecraft_id); for (int i = 0; i < 3; ++i) { ofs_sa << fixed << setprecision(10) << esti_pos[i] - true_pos[i] << ","; diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 842e1bce0..200bdcefb 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -76,9 +76,9 @@ class GnssSat_coordinate { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available - * @param [in] sat_id: Index of GNSS satellite + * @param [in] spacecraft_id: Index of GNSS satellite */ - bool GetWhetherValid(int sat_id) const; + bool GetWhetherValid(int spacecraft_id) const; protected: /** @@ -156,15 +156,15 @@ class GnssSat_position : public GnssSat_coordinate { /** * @fn GetSatEcef * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatEcef(int sat_id) const; + libra::Vector<3> GetSatEcef(int spacecraft_id) const; /** * @fn GetSatEci * @brief Return GNSS satellite position vector in the ECI frame [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatEci(int sat_id) const; + libra::Vector<3> GetSatEci(int spacecraft_id) const; private: std::vector> gnss_sat_ecef_; //!< List of GNSS satellite position at specific time in the ECEF frame [m] @@ -214,9 +214,9 @@ class GnssSat_clock : public GnssSat_coordinate { /** * @fn GetSatClock * @brief Return GNSS satellite clock in distance expression [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - double GetSatClock(int sat_id) const; + double GetSatClock(int spacecraft_id) const; private: std::vector gnss_sat_clock_; //!< List of clock bias of all GNSS satellites at specific time expressed in distance [m] @@ -273,27 +273,27 @@ class GnssSat_Info { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available for both position and clock information - * @param [in] sat_id: Index of GNSS satellite + * @param [in] spacecraft_id: Index of GNSS satellite */ - bool GetWhetherValid(int sat_id) const; + bool GetWhetherValid(int spacecraft_id) const; /** * @fn GetSatellitePositionEcef * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatellitePositionEcef(int sat_id) const; + libra::Vector<3> GetSatellitePositionEcef(int spacecraft_id) const; /** * @fn GetSatellitePositionEci * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatellitePositionEci(int sat_id) const; + libra::Vector<3> GetSatellitePositionEci(int spacecraft_id) const; /** * @fn GetSatelliteClock * @brief Return GNSS satellite clock in distance expression [m] - * @param [in] sat_id: GNSS satellite ID defined in this class + * @param [in] spacecraft_id: GNSS satellite ID defined in this class */ - double GetSatelliteClock(int sat_id) const; + double GetSatelliteClock(int spacecraft_id) const; /** * @fn GetGnssSatPos * @brief Return GNSS satellite position information class @@ -348,15 +348,15 @@ class GnssSatellites : public ILoggable { /** * @fn SetUp * @brief Setup both true and estimated GNSS satellite information - * @param [in] sim_time: Simulation time information + * @param [in] simulation_time: Simulation time information */ - void SetUp(const SimulationTime* sim_time); + void SetUp(const SimulationTime* simulation_time); /** * @fn Update * @brief Update both true and estimated GNSS satellite information - * @param [in] sim_time: Simulation time information + * @param [in] simulation_time: Simulation time information */ - void Update(const SimulationTime* sim_time); + void Update(const SimulationTime* simulation_time); /** * @fn GetIndexFromID @@ -381,9 +381,9 @@ class GnssSatellites : public ILoggable { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available for both position and clock for both true and estimated value - * @param [in] sat_id: Index of GNSS satellite + * @param [in] spacecraft_id: Index of GNSS satellite */ - bool GetWhetherValid(int sat_id) const; + bool GetWhetherValid(int spacecraft_id) const; /** * @fn GetStartUnixTime * @brief Return start unix time @@ -403,62 +403,64 @@ class GnssSatellites : public ILoggable { /** * @fn GetSatellitePositionEcef * @brief Return GNSS satellite position in the ECEF frame [m] - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID */ - libra::Vector<3> GetSatellitePositionEcef(const int sat_id) const; + libra::Vector<3> GetSatellitePositionEcef(const int spacecraft_id) const; /** * @fn GetSatellitePositionEci * @brief Return GNSS satellite position in the ECI frame [m] - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID */ - libra::Vector<3> GetSatellitePositionEci(const int sat_id) const; + libra::Vector<3> GetSatellitePositionEci(const int spacecraft_id) const; /** * @fn GetSatelliteClock * @brief Return GNSS satellite clock - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID */ - double GetSatelliteClock(const int sat_id) const; + double GetSatelliteClock(const int spacecraft_id) const; /** * @fn GetPseudoRangeECEF * @brief Calculate pseudo range between receiver and a GNSS satellite - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECEF frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Pseudo range [m] */ - double GetPseudoRangeECEF(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + double GetPseudoRangeECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; /** * @fn GetPseudoRangeECI * @brief Calculate pseudo range between receiver and a GNSS satellite - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECI frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Pseudo range [m] */ - double GetPseudoRangeECI(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + double GetPseudoRangeECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; /** * @fn GetCarrierPhaseECEF * @brief Calculate carrier phase observed by a receiver for a GNSS satellite - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECEF frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Carrier phase cycle and bias [-] */ - std::pair GetCarrierPhaseECEF(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + std::pair GetCarrierPhaseECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, + const double frequency) const; /** * @fn GetCarrierPhaseECI * @brief Calculate carrier phase observed by a receiver for a GNSS satellite - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECI frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Carrier phase cycle and bias [-] */ - std::pair GetCarrierPhaseECI(const int sat_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + std::pair GetCarrierPhaseECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, + const double frequency) const; // Override ILoggable /** @@ -489,13 +491,13 @@ class GnssSatellites : public ILoggable { * @fn AddIonosphericDelay * @brief Calculation of ionospheric delay * @note TODO: Ionospheric delay very Miscellaneous need to fix - * @param [in] sat_id: GNSS satellite ID + * @param [in] spacecraft_id: GNSS satellite ID * @param [in] rec_position: Receiver position [m] * @param [in] frequency: Frequency [MHz] * @param [in] flag: The frame definition of the receiver position (ECI or ECEF) * @return Ionospheric delay [m] */ - double AddIonosphericDelay(const int sat_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const; + double AddIonosphericDelay(const int spacecraft_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const; bool is_calc_enabled_ = true; //!< Flag to manage the GNSS satellite position calculation GnssSat_Info true_info_; //!< True information of GNSS satellites diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 1de3c1b15..8f04f9db0 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -16,9 +16,9 @@ SampleCase::~SampleCase() { delete sample_sat_; } void SampleCase::Initialize() { // Instantiate the target of the simulation - // `sat_id` corresponds to the index of `sat_file` in Simbase.ini - const int sat_id = 0; - sample_sat_ = new SampleSat(&sim_config_, glo_env_, sat_id); + // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini + const int spacecraft_id = 0; + sample_sat_ = new SampleSat(&sim_config_, glo_env_, spacecraft_id); const int gs_id = 0; sample_gs_ = new SampleGS(&sim_config_, gs_id); diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp index 91e9ed044..da0481966 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp @@ -7,6 +7,6 @@ #include -InterSatComm::InterSatComm(const SimulationConfig* sim_config) { UNUSED(sim_config); } +InterSatComm::InterSatComm(const SimulationConfig* simulation_configuration) { UNUSED(simulation_configuration); } InterSatComm::~InterSatComm() {} diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp index 49992e987..017e5b0fd 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp @@ -18,7 +18,7 @@ class InterSatComm { * @fn InterSatComm * @brief Constructor */ - InterSatComm(const SimulationConfig* sim_config); + InterSatComm(const SimulationConfig* simulation_configuration); /** * @fn ~InterSatComm * @brief Destructor diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 33aa4c247..0b09b3a9a 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -33,13 +33,13 @@ void RelativeInformation::Update() { } } -void RelativeInformation::RegisterDynamicsInfo(const int sat_id, const Dynamics* dynamics) { - dynamics_database_.emplace(sat_id, dynamics); +void RelativeInformation::RegisterDynamicsInfo(const int spacecraft_id, const Dynamics* dynamics) { + dynamics_database_.emplace(spacecraft_id, dynamics); ResizeLists(); } -void RelativeInformation::RemoveDynamicsInfo(const int sat_id) { - dynamics_database_.erase(sat_id); +void RelativeInformation::RemoveDynamicsInfo(const int spacecraft_id) { + dynamics_database_.erase(spacecraft_id); ResizeLists(); } diff --git a/src/simulation/multiple_spacecraft/relative_information.hpp b/src/simulation/multiple_spacecraft/relative_information.hpp index 4944f9e55..5dcea0f8a 100644 --- a/src/simulation/multiple_spacecraft/relative_information.hpp +++ b/src/simulation/multiple_spacecraft/relative_information.hpp @@ -37,16 +37,16 @@ class RelativeInformation : public ILoggable { /** * @fn RegisterDynamicsInfo * @brief Register dynamics information of target spacecraft - * @param [in] sat_id: ID of target spacecraft + * @param [in] spacecraft_id: ID of target spacecraft * @param [in] dynamics: Dynamics information of the target spacecraft */ - void RegisterDynamicsInfo(const int sat_id, const Dynamics* dynamics); + void RegisterDynamicsInfo(const int spacecraft_id, const Dynamics* dynamics); /** * @fn RegisterDynamicsInfo * @brief Remove dynamics information of target spacecraft - * @param [in] sat_id: ID of target spacecraft + * @param [in] spacecraft_id: ID of target spacecraft */ - void RemoveDynamicsInfo(const int sat_id); + void RemoveDynamicsInfo(const int spacecraft_id); // Override classes for ILoggable /** diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 75c6f04be..cff5665c5 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -10,9 +10,10 @@ #include "sample_port_configuration.hpp" SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, - const GlobalEnvironment* glo_env, const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id) - : config_(config), dynamics_(dynamics), structure_(structure), local_environment_(local_environment), glo_env_(glo_env) { - IniAccess iniAccess = IniAccess(config_->spacecraft_file_list_[sat_id]); + const GlobalEnvironment* global_environment, const SimulationConfig* config, ClockGenerator* clock_gen, + const int spacecraft_id) + : config_(config), dynamics_(dynamics), structure_(structure), local_environment_(local_environment), glo_env_(global_environment) { + IniAccess iniAccess = IniAccess(config_->spacecraft_file_list_[spacecraft_id]); // PCU power port connection pcu_ = new PowerControlUnit(clock_gen); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 2bb13f0ec..10d8bf3aa 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -53,8 +53,8 @@ class SampleComponents : public InstalledComponents { * @fn SampleComponents * @brief Constructor */ - SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* glo_env, - const SimulationConfig* config, ClockGenerator* clock_gen, const int sat_id); + SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, + const GlobalEnvironment* global_environment, const SimulationConfig* config, ClockGenerator* clock_gen, const int spacecraft_id); /** * @fn ~SampleComponents * @brief Destructor diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 1779ff913..1bc37c63c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -10,7 +10,9 @@ #include "sample_components.hpp" -SampleSat::SampleSat(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : Spacecraft(sim_config, glo_env, sat_id) { - sample_components_ = new SampleComponents(dynamics_, structure_, local_environment_, glo_env, sim_config, &clock_generator_, sat_id); +SampleSat::SampleSat(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) + : Spacecraft(simulation_configuration, global_environment, spacecraft_id) { + sample_components_ = + new SampleComponents(dynamics_, structure_, local_environment_, global_environment, simulation_configuration, &clock_generator_, spacecraft_id); components_ = sample_components_; } diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index 561300a8e..b89596e57 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -21,7 +21,7 @@ class SampleSat : public Spacecraft { * @fn SampleSat * @brief Constructor */ - SampleSat(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id); + SampleSat(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn GetInstalledComponents diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index 91d355094..ffeaf710d 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -8,13 +8,15 @@ #include #include -Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) : spacecraft_id_(sat_id) { - Initialize(sim_config, glo_env, sat_id); +Spacecraft::Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) + : spacecraft_id_(spacecraft_id) { + Initialize(simulation_configuration, global_environment, spacecraft_id); } -Spacecraft::Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id) - : spacecraft_id_(sat_id) { - Initialize(sim_config, glo_env, rel_info, sat_id); +Spacecraft::Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + RelativeInformation* relative_information, const int spacecraft_id) + : spacecraft_id_(spacecraft_id) { + Initialize(simulation_configuration, global_environment, relative_information, spacecraft_id); } Spacecraft::~Spacecraft() { @@ -28,30 +30,32 @@ Spacecraft::~Spacecraft() { delete components_; } -void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id) { +void Spacecraft::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { clock_generator_.ClearTimerCount(); - structure_ = new Structure(sim_config, sat_id); - local_environment_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), sat_id, structure_); - disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); + structure_ = new Structure(simulation_configuration, spacecraft_id); + local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); + dynamics_ = new Dynamics(simulation_configuration, &(global_environment->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), + spacecraft_id, structure_); + disturbances_ = new Disturbances(simulation_configuration, spacecraft_id, structure_, global_environment); - sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); + simulation_configuration->main_logger_->CopyFileToLogDirectory(simulation_configuration->spacecraft_file_list_[spacecraft_id]); relative_information_ = nullptr; } -void Spacecraft::Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id) { +void Spacecraft::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + RelativeInformation* relative_information, const int spacecraft_id) { clock_generator_.ClearTimerCount(); - structure_ = new Structure(sim_config, sat_id); - local_environment_ = new LocalEnvironment(sim_config, glo_env, sat_id); - dynamics_ = - new Dynamics(sim_config, &(glo_env->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), sat_id, structure_, rel_info); - disturbances_ = new Disturbances(sim_config, sat_id, structure_, glo_env); + structure_ = new Structure(simulation_configuration, spacecraft_id); + local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); + dynamics_ = new Dynamics(simulation_configuration, &(global_environment->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), + spacecraft_id, structure_, relative_information); + disturbances_ = new Disturbances(simulation_configuration, spacecraft_id, structure_, global_environment); - sim_config->main_logger_->CopyFileToLogDirectory(sim_config->spacecraft_file_list_[sat_id]); + simulation_configuration->main_logger_->CopyFileToLogDirectory(simulation_configuration->spacecraft_file_list_[spacecraft_id]); - relative_information_ = rel_info; - relative_information_->RegisterDynamicsInfo(sat_id, dynamics_); + relative_information_ = relative_information; + relative_information_->RegisterDynamicsInfo(spacecraft_id, dynamics_); } void Spacecraft::LogSetup(Logger& logger) { @@ -61,15 +65,15 @@ void Spacecraft::LogSetup(Logger& logger) { components_->LogSetup(logger); } -void Spacecraft::Update(const SimulationTime* sim_time) { +void Spacecraft::Update(const SimulationTime* simulation_time) { dynamics_->ClearForceTorque(); // Update local environment and disturbance - local_environment_->Update(dynamics_, sim_time); - disturbances_->Update(*local_environment_, *dynamics_, sim_time); + local_environment_->Update(dynamics_, simulation_time); + disturbances_->Update(*local_environment_, *dynamics_, simulation_time); // Update components - clock_generator_.UpdateComponents(sim_time); + clock_generator_.UpdateComponents(simulation_time); // Add generated force and torque by disturbances dynamics_->AddAcceleration_i_m_s2(disturbances_->GetAcceleration_i_m_s2()); @@ -81,7 +85,7 @@ void Spacecraft::Update(const SimulationTime* sim_time) { dynamics_->AddForce_b_N(components_->GenerateForce_N_b()); // Propagate dynamics - dynamics_->Update(sim_time, &(local_environment_->GetCelestialInformation())); + dynamics_->Update(simulation_time, &(local_environment_->GetCelestialInformation())); } void Spacecraft::Clear(void) { dynamics_->ClearForceTorque(); } diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 9706c516f..e835b461e 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -25,12 +25,13 @@ class Spacecraft { * @fn Spacecraft * @brief Constructor for single satellite simulation */ - Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id); + Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Spacecraft * @brief Constructor for multiple satellite simulation */ - Spacecraft(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id); + Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, + const int spacecraft_id); /** * @fn ~Spacecraft @@ -47,18 +48,19 @@ class Spacecraft { * @fn Initialize * @brief Initialize function for single spacecraft simulation */ - virtual void Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, const int sat_id); + virtual void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Initialize * @brief Initialize function for multiple spacecraft simulation */ - virtual void Initialize(SimulationConfig* sim_config, const GlobalEnvironment* glo_env, RelativeInformation* rel_info, const int sat_id); + virtual void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + RelativeInformation* relative_information, const int spacecraft_id); /** * @fn Update * @brief Update all states related with the spacecraft */ - virtual void Update(const SimulationTime* sim_time); + virtual void Update(const SimulationTime* simulation_time); /** * @fn Clear diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 7d26fc817..f6e89ab50 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -8,19 +8,19 @@ #include #include -Structure::Structure(SimulationConfig* sim_config, const int sat_id) { Initialize(sim_config, sat_id); } +Structure::Structure(SimulationConfig* simulation_configuration, const int spacecraft_id) { Initialize(simulation_configuration, spacecraft_id); } Structure::~Structure() { delete kinnematics_params_; delete rmm_params_; } -void Structure::Initialize(SimulationConfig* sim_config, const int sat_id) { +void Structure::Initialize(SimulationConfig* simulation_configuration, const int spacecraft_id) { // Read file name - IniAccess conf = IniAccess(sim_config->spacecraft_file_list_[sat_id]); + IniAccess conf = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); // Save ini file - sim_config->main_logger_->CopyFileToLogDirectory(ini_fname); + simulation_configuration->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize kinnematics_params_ = new KinematicsParams(InitKinematicsParams(ini_fname)); surfaces_ = InitSurfaces(ini_fname); diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 558cd6e47..d6cd4484c 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -24,7 +24,7 @@ class Structure { * @fn Structure * @brief Constructor */ - Structure(SimulationConfig* sim_config, const int sat_id); + Structure(SimulationConfig* simulation_configuration, const int spacecraft_id); /** * @fn ~Structure * @brief Destructor @@ -34,7 +34,7 @@ class Structure { * @fn Initialize * @brief Initialize function */ - void Initialize(SimulationConfig* sim_config, const int sat_id); + void Initialize(SimulationConfig* simulation_configuration, const int spacecraft_id); // Getter /** From 43598bfcee7b8f07fd172ebe4c7349aa656aa05d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:40:59 +0100 Subject: [PATCH 0883/1086] Fix public function name --- .../real/communication/ground_station_calculator.cpp | 2 +- src/simulation/ground_station/ground_station.cpp | 2 +- src/simulation/spacecraft/spacecraft.hpp | 8 ++++---- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 3ecdaa42a..f2a0a321b 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -28,7 +28,7 @@ GroundStationCalculator::~GroundStationCalculator() {} void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { - bool is_visible = ground_station.IsVisible(spacecraft.GetSatID()); + bool is_visible = ground_station.IsVisible(spacecraft.GetSpacecraftId()); if (is_visible) { max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 808fe3327..93e65d6d4 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -48,7 +48,7 @@ void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacec Matrix<3, 3> dcm_ecef2eci = Transpose(celes_rotation.GetDcmJ2000ToXcxf()); gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; - is_visible_[spacecraft.GetSatID()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); + is_visible_[spacecraft.GetSpacecraftId()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); } bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index e835b461e..e84138eb7 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -81,10 +81,10 @@ class Spacecraft { */ inline const Dynamics& GetDynamics() const { return *dynamics_; } /** - * @fn GetlocalEnv + * @fn GetLocalEnvironment * @brief Get local environment around the spacecraft */ - inline const LocalEnvironment& GetLocalEnv() const { return *local_environment_; } + inline const LocalEnvironment& GetLocalEnvironment() const { return *local_environment_; } /** * @fn GetDisturbances * @brief Get disturbance acting of the spacecraft @@ -101,10 +101,10 @@ class Spacecraft { */ inline const InstalledComponents& GetInstalledComponents() const { return *components_; } /** - * @fn GetSatID + * @fn GetSpacecraftId * @brief Get ID of the spacecraft */ - inline int GetSatID() const { return spacecraft_id_; } + inline unsigned int GetSpacecraftId() const { return spacecraft_id_; } protected: ClockGenerator clock_generator_; //!< Origin of clock for the spacecraft From c26abb85b61c2e8c5cda3f2ab8dfae155c58824a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:42:16 +0100 Subject: [PATCH 0884/1086] Fix public function name --- .../spacecraft/installed_components.cpp | 12 +++++----- .../spacecraft/installed_components.hpp | 8 +++---- .../sample_spacecraft/sample_components.cpp | 24 +++++++++---------- .../sample_spacecraft/sample_components.hpp | 8 +++---- src/simulation/spacecraft/spacecraft.cpp | 4 ++-- 5 files changed, 28 insertions(+), 28 deletions(-) diff --git a/src/simulation/spacecraft/installed_components.cpp b/src/simulation/spacecraft/installed_components.cpp index 6f5aa13c9..015b606ac 100644 --- a/src/simulation/spacecraft/installed_components.cpp +++ b/src/simulation/spacecraft/installed_components.cpp @@ -7,14 +7,14 @@ #include -libra::Vector<3> InstalledComponents::GenerateForce_N_b() { - libra::Vector<3> force_N_b_(0.0); - return force_N_b_; +libra::Vector<3> InstalledComponents::GenerateForce_b_N() { + libra::Vector<3> force_b_N_(0.0); + return force_b_N_; } -libra::Vector<3> InstalledComponents::GenerateTorque_Nm_b() { - libra::Vector<3> torque_Nm_b_(0.0); - return torque_Nm_b_; +libra::Vector<3> InstalledComponents::GenerateTorque_b_Nm() { + libra::Vector<3> torque_b_Nm_(0.0); + return torque_b_Nm_; } void InstalledComponents::LogSetup(Logger& logger) { UNUSED(logger); } diff --git a/src/simulation/spacecraft/installed_components.hpp b/src/simulation/spacecraft/installed_components.hpp index abb060320..2132ed09c 100644 --- a/src/simulation/spacecraft/installed_components.hpp +++ b/src/simulation/spacecraft/installed_components.hpp @@ -22,18 +22,18 @@ class InstalledComponents { virtual ~InstalledComponents() {} /** - * @fn GenerateForce_N_b + * @fn GenerateForce_b_N * @brief Return force generated by components in unit Newton in body fixed frame * @details Users need to override this function to add force generated by components */ - virtual libra::Vector<3> GenerateForce_N_b(); + virtual libra::Vector<3> GenerateForce_b_N(); /** - * @fn GenerateTorque_Nm_b + * @fn GenerateTorque_b_Nm * @brief Return torque generated by components in unit Newton-meter in body fixed frame * @details Users need to override this function to add torque generated by components */ - virtual libra::Vector<3> GenerateTorque_Nm_b(); + virtual libra::Vector<3> GenerateTorque_b_Nm(); /** * @fn LogSetup diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index cff5665c5..d8049845c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -153,20 +153,20 @@ SampleComponents::~SampleComponents() { delete hils_port_manager_; // delete after exp_hils } -libra::Vector<3> SampleComponents::GenerateForce_N_b() { - libra::Vector<3> force_N_b_(0.0); - force_N_b_ += thruster_->GetOutputThrust_b_N(); - force_N_b_ += force_generator_->GetGeneratedForce_b_N(); - return force_N_b_; +libra::Vector<3> SampleComponents::GenerateForce_b_N() { + libra::Vector<3> force_b_N_(0.0); + force_b_N_ += thruster_->GetOutputThrust_b_N(); + force_b_N_ += force_generator_->GetGeneratedForce_b_N(); + return force_b_N_; } -libra::Vector<3> SampleComponents::GenerateTorque_Nm_b() { - libra::Vector<3> torque_Nm_b_(0.0); - torque_Nm_b_ += mag_torquer_->GetOutputTorque_b_Nm(); - torque_Nm_b_ += rw_->GetOutputTorque_b_Nm(); - torque_Nm_b_ += thruster_->GetOutputTorque_b_Nm(); - torque_Nm_b_ += torque_generator_->GetGeneratedTorque_b_Nm(); - return torque_Nm_b_; +libra::Vector<3> SampleComponents::GenerateTorque_b_Nm() { + libra::Vector<3> torque_b_Nm_(0.0); + torque_b_Nm_ += mag_torquer_->GetOutputTorque_b_Nm(); + torque_b_Nm_ += rw_->GetOutputTorque_b_Nm(); + torque_b_Nm_ += thruster_->GetOutputTorque_b_Nm(); + torque_b_Nm_ += torque_generator_->GetGeneratedTorque_b_Nm(); + return torque_b_Nm_; } void SampleComponents::LogSetup(Logger& logger) { diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 10d8bf3aa..0c808419b 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -63,15 +63,15 @@ class SampleComponents : public InstalledComponents { // Override functions for InstalledComponents /** - * @fn GenerateForce_N_b + * @fn GenerateForce_b_N * @brief Return force generated by components in unit Newton in body fixed frame */ - libra::Vector<3> GenerateForce_N_b(); + libra::Vector<3> GenerateForce_b_N(); /** - * @fn GenerateTorque_Nm_b + * @fn GenerateTorque_b_Nm * @brief Return torque generated by components in unit Newton-meter in body fixed frame */ - libra::Vector<3> GenerateTorque_Nm_b(); + libra::Vector<3> GenerateTorque_b_Nm(); /** * @fn LogSetup * @brief Setup the logger for components diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index ffeaf710d..de49a944b 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -81,8 +81,8 @@ void Spacecraft::Update(const SimulationTime* simulation_time) { dynamics_->AddForce_b_N(disturbances_->GetForce_b_N()); // Add generated force and torque by components - dynamics_->AddTorque_b_Nm(components_->GenerateTorque_Nm_b()); - dynamics_->AddForce_b_N(components_->GenerateForce_N_b()); + dynamics_->AddTorque_b_Nm(components_->GenerateTorque_b_Nm()); + dynamics_->AddForce_b_N(components_->GenerateForce_b_N()); // Propagate dynamics dynamics_->Update(simulation_time, &(local_environment_->GetCelestialInformation())); From 1d7e842ece6f16f482b120e69bd0148469ab6638 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:45:10 +0100 Subject: [PATCH 0885/1086] Remove using --- .../real/aocs/initialize_magnetorquer.cpp | 6 +++--- src/disturbances/geopotential.cpp | 6 +++--- .../ground_station/ground_station.cpp | 2 +- .../structure/initialize_structure.cpp | 8 ++++---- .../structure/kinematics_parameters.cpp | 2 +- .../structure/kinematics_parameters.hpp | 18 ++++++++---------- 6 files changed, 20 insertions(+), 22 deletions(-) diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 15a82aeba..0e8b371af 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -16,9 +16,9 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Vector sf_vec; + libra::Vector sf_vec; magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); - Matrix scale_factor; + libra::Matrix scale_factor; for (size_t i = 0; i < kMtqDimension; i++) { for (size_t j = 0; j < kMtqDimension; j++) { scale_factor[i][j] = sf_vec[i * kMtqDimension + j]; @@ -63,7 +63,7 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_ Vector sf_vec; magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); - Matrix scale_factor; + libra::Matrix scale_factor; for (size_t i = 0; i < kMtqDimension; i++) { for (size_t j = 0; j < kMtqDimension; j++) { scale_factor[i][j] = sf_vec[i * kMtqDimension + j]; diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 352ea3adf..29a8af9b4 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -78,12 +78,12 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam time_ms_ = static_cast(chrono::duration_cast(end - start).count() / 1000.0); #endif - Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelestialInformation().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); - Matrix<3, 3> trans_ecef2eci = Transpose(trans_eci2ecef_); + libra::Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelestialInformation().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); + libra::Matrix<3, 3> trans_ecef2eci = Transpose(trans_eci2ecef_); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } -void GeoPotential::CalcAccelerationEcef(const Vector<3> &position_ecef_m) { +void GeoPotential::CalcAccelerationEcef(const libra::Vector<3> &position_ecef_m) { ecef_x_m_ = position_ecef_m[0]; ecef_y_m_ = position_ecef_m[1]; ecef_z_m_ = position_ecef_m[2]; diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 93e65d6d4..64fe11e06 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -45,7 +45,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft) { - Matrix<3, 3> dcm_ecef2eci = Transpose(celes_rotation.GetDcmJ2000ToXcxf()); + libra::Matrix<3, 3> dcm_ecef2eci = Transpose(celes_rotation.GetDcmJ2000ToXcxf()); gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; is_visible_[spacecraft.GetSpacecraftId()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index b2e2c79af..a5230653e 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -13,11 +13,11 @@ KinematicsParams InitKinematicsParams(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "KINEMATIC_PARAMETERS"; - Vector<3> cg_b; + libra::Vector<3> cg_b; conf.ReadVector(section, "center_of_gravity_b_m", cg_b); double mass = conf.ReadDouble(section, "mass_kg"); - Vector<9> inertia_vec; - Matrix<3, 3> inertia_tensor; + libra::Vector<9> inertia_vec; + libra::Matrix<3, 3> inertia_tensor; conf.ReadVector(section, "inertia_tensor_kgm2", inertia_vec); for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { @@ -110,7 +110,7 @@ RMMParams InitRMMParams(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "RESIDUAL_MAGNETIC_MOMENT"; - Vector<3> rmm_const_b; + libra::Vector<3> rmm_const_b; conf.ReadVector(section, "rmm_constant_b_Am2", rmm_const_b); double rmm_rwdev = conf.ReadDouble(section, "rmm_random_walk_speed_Am2"); double rmm_rwlimit = conf.ReadDouble(section, "rmm_random_walk_limit_Am2"); diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.cpp b/src/simulation/spacecraft/structure/kinematics_parameters.cpp index 3200aa0ae..c1fc1cb85 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.cpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.cpp @@ -5,5 +5,5 @@ #include "kinematics_parameters.hpp" -KinematicsParams::KinematicsParams(Vector<3> cg_b, double mass, Matrix<3, 3> inertia_tensor) +KinematicsParams::KinematicsParams(libra::Vector<3> cg_b, double mass, libra::Matrix<3, 3> inertia_tensor) : cg_b_(cg_b), mass_(mass), inertia_tensor_(inertia_tensor) {} \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 0402773fb..f2942908d 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -8,8 +8,6 @@ #include #include -using libra::Matrix; -using libra::Vector; /** * @class KinematicsParams @@ -21,7 +19,7 @@ class KinematicsParams { * @fn KinematicsParams * @brief Constructor */ - KinematicsParams(Vector<3> cg_b, double mass, Matrix<3, 3> inertia_tensor); + KinematicsParams(libra::Vector<3> cg_b, double mass, libra::Matrix<3, 3> inertia_tensor); /** * @fn ~KinematicsParams * @brief Destructor @@ -33,7 +31,7 @@ class KinematicsParams { * @fn GetCGb * @brief Return Position vector of center of gravity at body frame [m] */ - inline const Vector<3>& GetCGb() const { return cg_b_; } + inline const libra::Vector<3>& GetCGb() const { return cg_b_; } /** * @fn GetMass * @brief Return Mass of the satellite [kg] @@ -43,7 +41,7 @@ class KinematicsParams { * @fn GetInertiaTensor * @brief Return Inertia tensor at body frame [kgm2] */ - inline const Matrix<3, 3>& GetInertiaTensor() const { return inertia_tensor_; } + inline const libra::Matrix<3, 3>& GetInertiaTensor() const { return inertia_tensor_; } // Setter /** @@ -51,7 +49,7 @@ class KinematicsParams { * @brief Set center of gravity vector at the body frame [m] * @param [in] center_of_gravity_vector_b_m: Center of gravity vector at the body frame [m] */ - inline void SetCenterOfGravityVector_b_m(const Vector<3> center_of_gravity_vector_b_m) { cg_b_ = center_of_gravity_vector_b_m; } + inline void SetCenterOfGravityVector_b_m(const libra::Vector<3> center_of_gravity_vector_b_m) { cg_b_ = center_of_gravity_vector_b_m; } /** * @fn SetMass_kg * @brief Set mass of the satellite @@ -75,15 +73,15 @@ class KinematicsParams { * @brief Inertia tensor at body frame * @param [in] inertia_tensor_b_kgm2: Inertia tensor at body frame [kgm2] */ - inline void SetInertiaTensor_b_kgm2(const Matrix<3, 3> inertia_tensor_b_kgm2) { + inline void SetInertiaTensor_b_kgm2(const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { // TODO add assertion check inertia_tensor_ = inertia_tensor_b_kgm2; } private: - Vector<3> cg_b_; //!< Position vector of center of gravity at body frame [m] - double mass_; //!< Mass of the satellite [kg] - Matrix<3, 3> inertia_tensor_; //!< Inertia tensor at body frame [kgm2] + libra::Vector<3> cg_b_; //!< Position vector of center of gravity at body frame [m] + double mass_; //!< Mass of the satellite [kg] + libra::Matrix<3, 3> inertia_tensor_; //!< Inertia tensor at body frame [kgm2] }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_HPP_ From 4abd8202caf37a9ab111a0e9bc5969074900bc5e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:46:51 +0100 Subject: [PATCH 0886/1086] Fix private variables --- .../structure/kinematics_parameters.cpp | 2 +- .../structure/kinematics_parameters.hpp | 22 ++++++++++--------- 2 files changed, 13 insertions(+), 11 deletions(-) diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.cpp b/src/simulation/spacecraft/structure/kinematics_parameters.cpp index c1fc1cb85..cbac35f72 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.cpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.cpp @@ -6,4 +6,4 @@ #include "kinematics_parameters.hpp" KinematicsParams::KinematicsParams(libra::Vector<3> cg_b, double mass, libra::Matrix<3, 3> inertia_tensor) - : cg_b_(cg_b), mass_(mass), inertia_tensor_(inertia_tensor) {} \ No newline at end of file + : center_of_gravity_b_m_(cg_b), mass_kg_(mass), inertia_tensor_b_kgm2_(inertia_tensor) {} \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index f2942908d..69ca2cd6d 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -31,17 +31,17 @@ class KinematicsParams { * @fn GetCGb * @brief Return Position vector of center of gravity at body frame [m] */ - inline const libra::Vector<3>& GetCGb() const { return cg_b_; } + inline const libra::Vector<3>& GetCGb() const { return center_of_gravity_b_m_; } /** * @fn GetMass * @brief Return Mass of the satellite [kg] */ - inline const double& GetMass() const { return mass_; } + inline const double& GetMass() const { return mass_kg_; } /** * @fn GetInertiaTensor * @brief Return Inertia tensor at body frame [kgm2] */ - inline const libra::Matrix<3, 3>& GetInertiaTensor() const { return inertia_tensor_; } + inline const libra::Matrix<3, 3>& GetInertiaTensor() const { return inertia_tensor_b_kgm2_; } // Setter /** @@ -49,14 +49,16 @@ class KinematicsParams { * @brief Set center of gravity vector at the body frame [m] * @param [in] center_of_gravity_vector_b_m: Center of gravity vector at the body frame [m] */ - inline void SetCenterOfGravityVector_b_m(const libra::Vector<3> center_of_gravity_vector_b_m) { cg_b_ = center_of_gravity_vector_b_m; } + inline void SetCenterOfGravityVector_b_m(const libra::Vector<3> center_of_gravity_vector_b_m) { + center_of_gravity_b_m_ = center_of_gravity_vector_b_m; + } /** * @fn SetMass_kg * @brief Set mass of the satellite * @param [in] mass_kg: Mass of the satellite [kg] */ inline void SetMass_kg(const double mass_kg) { - if (mass_kg > 0.0) mass_ = mass_kg; + if (mass_kg > 0.0) mass_kg_ = mass_kg; } /** * @fn AddMass_kg @@ -65,7 +67,7 @@ class KinematicsParams { * @note Normally, this function is used to decrease the mass due to the fuel consumption. */ inline void AddMass_kg(const double mass_kg) { - double temp_mass_kg = mass_ + mass_kg; + double temp_mass_kg = mass_kg_ + mass_kg; SetMass_kg(temp_mass_kg); } /** @@ -75,13 +77,13 @@ class KinematicsParams { */ inline void SetInertiaTensor_b_kgm2(const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { // TODO add assertion check - inertia_tensor_ = inertia_tensor_b_kgm2; + inertia_tensor_b_kgm2_ = inertia_tensor_b_kgm2; } private: - libra::Vector<3> cg_b_; //!< Position vector of center of gravity at body frame [m] - double mass_; //!< Mass of the satellite [kg] - libra::Matrix<3, 3> inertia_tensor_; //!< Inertia tensor at body frame [kgm2] + libra::Vector<3> center_of_gravity_b_m_; //!< Position vector of center of gravity at body frame [m] + double mass_kg_; //!< Mass of the satellite [kg] + libra::Matrix<3, 3> inertia_tensor_b_kgm2_; //!< Inertia tensor at body frame [kgm2] }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_KINEMATICS_PARAMETERS_HPP_ From 5ae9302c66b9134354afa3534d057796e1a0e3a0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:47:44 +0100 Subject: [PATCH 0887/1086] Fix public function name --- src/components/real/propulsion/simple_thruster.cpp | 2 +- src/disturbances/disturbances.cpp | 7 ++++--- src/disturbances/gravity_gradient.cpp | 3 ++- src/dynamics/attitude/attitude.hpp | 4 ++-- src/dynamics/dynamics.cpp | 2 +- src/dynamics/dynamics.hpp | 2 +- .../spacecraft/structure/kinematics_parameters.hpp | 12 ++++++------ 7 files changed, 17 insertions(+), 15 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index cbefcff44..f82a54eff 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -50,7 +50,7 @@ void SimpleThruster::MainRoutine(const int time_count) { UNUSED(time_count); CalcThrust(); - CalcTorque(structure_->GetKinematicsParams().GetCGb()); + CalcTorque(structure_->GetKinematicsParams().GetCenterOfGravity_b_m()); } void SimpleThruster::PowerOffRoutine() { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 8614b5d7c..ae8f345a9 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -71,8 +71,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* simulation_config InitGravityGradient(initialize_file_name_, global_environment->GetCelestialInformation().GetCenterBodyGravityConstant_m3_s2())); disturbances_list_.push_back(gg_dist); - SolarRadiationPressureDisturbance* srp_dist = new SolarRadiationPressureDisturbance( - InitSolarRadiationPressureDisturbance(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); + SolarRadiationPressureDisturbance* srp_dist = new SolarRadiationPressureDisturbance(InitSolarRadiationPressureDisturbance( + initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCenterOfGravity_b_m())); disturbances_list_.push_back(srp_dist); ThirdBodyGravity* third_body_gravity = @@ -81,7 +81,8 @@ void Disturbances::InitializeInstances(const SimulationConfig* simulation_config if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) - AirDrag* air_dist = new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCGb())); + AirDrag* air_dist = + new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCenterOfGravity_b_m())); disturbances_list_.push_back(air_dist); MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetRMMParams())); diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 546e9511a..7390771db 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -18,7 +18,8 @@ GravityGradient::GravityGradient(const double gravity_constant_m3_s2, const bool void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor - CalcTorque_b_Nm(local_environment.GetCelestialInformation().GetCenterBodyPositionFromSpacecraft_b_m(), dynamics.GetAttitude().GetInertiaTensor()); + CalcTorque_b_Nm(local_environment.GetCelestialInformation().GetCenterBodyPositionFromSpacecraft_b_m(), + dynamics.GetAttitude().GetInertiaTensor_b_kgm2()); } libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 15b4d4beb..84f1e6d75 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -57,10 +57,10 @@ class Attitude : public ILoggable, public SimulationObject { */ inline double GetEnergy() const { return kinetic_energy_J_; } /** - * @fn GetInertiaTensor + * @fn GetInertiaTensor_b_kgm2 * @brief Return inertia tensor [kg m^2] */ - inline libra::Matrix<3, 3> GetInertiaTensor() const { return inertia_tensor_kgm2_; } + inline libra::Matrix<3, 3> GetInertiaTensor_b_kgm2() const { return inertia_tensor_kgm2_; } // Setter /** diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 5f435c33c..4aeee9634 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -29,7 +29,7 @@ void Dynamics::Initialize(SimulationConfig* simulation_configuration, const Simu simulation_time->GetOrbitRkStepTime_s(), simulation_time->GetCurrentTime_jd(), local_celestial_information->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", relative_information); attitude_ = InitAttitude(simulation_configuration->spacecraft_file_list_[spacecraft_id], orbit_, local_celestial_information, - simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor(), spacecraft_id); + simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor_b_kgm2(), spacecraft_id); temperature_ = InitTemperature(simulation_configuration->spacecraft_file_list_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); // To get initial value diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 75cf2e727..784604ac1 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -70,7 +70,7 @@ class Dynamics { * @param [in] force_b_N: Force in the body fixed frame [N] */ inline void AddForce_b_N(libra::Vector<3> force_b_N) { - orbit_->AddForce_b_N(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass()); + orbit_->AddForce_b_N(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass_kg()); } /** * @fn AddAcceleration_i_m_s2 diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 69ca2cd6d..206a6ae7c 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -28,20 +28,20 @@ class KinematicsParams { // Getter /** - * @fn GetCGb + * @fn GetCenterOfGravity_b_m * @brief Return Position vector of center of gravity at body frame [m] */ - inline const libra::Vector<3>& GetCGb() const { return center_of_gravity_b_m_; } + inline const libra::Vector<3>& GetCenterOfGravity_b_m() const { return center_of_gravity_b_m_; } /** - * @fn GetMass + * @fn GetMass_kg * @brief Return Mass of the satellite [kg] */ - inline const double& GetMass() const { return mass_kg_; } + inline const double& GetMass_kg() const { return mass_kg_; } /** - * @fn GetInertiaTensor + * @fn GetInertiaTensor_b_kgm2 * @brief Return Inertia tensor at body frame [kgm2] */ - inline const libra::Matrix<3, 3>& GetInertiaTensor() const { return inertia_tensor_b_kgm2_; } + inline const libra::Matrix<3, 3>& GetInertiaTensor_b_kgm2() const { return inertia_tensor_b_kgm2_; } // Setter /** From 7e0924485797f9f5d301b2d063bace7e8c2c6705 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:48:41 +0100 Subject: [PATCH 0888/1086] Fix function argument names --- src/components/real/propulsion/simple_thruster.hpp | 2 +- src/disturbances/surface_force.hpp | 2 +- .../spacecraft/structure/initialize_structure.cpp | 12 ++++++------ .../spacecraft/structure/kinematics_parameters.cpp | 4 ++-- .../spacecraft/structure/kinematics_parameters.hpp | 8 ++++---- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index 26b5f0588..2557048d8 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -128,7 +128,7 @@ class SimpleThruster : public Component, public ILoggable { /** * @fn CalcTorque * @brief Calculate generated torque - * @param [in] center_of_mass_b_m: Center of mass position at body frame [m] + * @param [in] center_of_mass_b_m: Center of mass_kg position at body frame [m] */ void CalcTorque(const Vector<3> center_of_mass_b_m); /** diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 8d5885992..ff4232200 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -38,7 +38,7 @@ class SurfaceForce : public SimpleDisturbance { protected: // Spacecraft Structure parameters const vector& surfaces_; //!< List of surfaces - const libra::Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass at body frame [m] + const libra::Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass_kg at body frame [m] // Internal calculated variables vector normal_coefficients_; //!< coefficients for out-plane force for each surface diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index a5230653e..bf9191fd2 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -13,19 +13,19 @@ KinematicsParams InitKinematicsParams(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "KINEMATIC_PARAMETERS"; - libra::Vector<3> cg_b; - conf.ReadVector(section, "center_of_gravity_b_m", cg_b); - double mass = conf.ReadDouble(section, "mass_kg"); + libra::Vector<3> center_of_gravity_b_m; + conf.ReadVector(section, "center_of_gravity_b_m", center_of_gravity_b_m); + double mass_kg = conf.ReadDouble(section, "mass_kg"); libra::Vector<9> inertia_vec; - libra::Matrix<3, 3> inertia_tensor; + libra::Matrix<3, 3> inertia_tensor_b_kgm2; conf.ReadVector(section, "inertia_tensor_kgm2", inertia_vec); for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { - inertia_tensor[i][j] = inertia_vec[i * 3 + j]; + inertia_tensor_b_kgm2[i][j] = inertia_vec[i * 3 + j]; } } - KinematicsParams kinematics_params(cg_b, mass, inertia_tensor); + KinematicsParams kinematics_params(center_of_gravity_b_m, mass_kg, inertia_tensor_b_kgm2); return kinematics_params; } diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.cpp b/src/simulation/spacecraft/structure/kinematics_parameters.cpp index cbac35f72..e1cfc572d 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.cpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.cpp @@ -5,5 +5,5 @@ #include "kinematics_parameters.hpp" -KinematicsParams::KinematicsParams(libra::Vector<3> cg_b, double mass, libra::Matrix<3, 3> inertia_tensor) - : center_of_gravity_b_m_(cg_b), mass_kg_(mass), inertia_tensor_b_kgm2_(inertia_tensor) {} \ No newline at end of file +KinematicsParams::KinematicsParams(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2) + : center_of_gravity_b_m_(center_of_gravity_b_m), mass_kg_(mass_kg), inertia_tensor_b_kgm2_(inertia_tensor_b_kgm2) {} \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index 206a6ae7c..a2957455c 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -19,7 +19,7 @@ class KinematicsParams { * @fn KinematicsParams * @brief Constructor */ - KinematicsParams(libra::Vector<3> cg_b, double mass, libra::Matrix<3, 3> inertia_tensor); + KinematicsParams(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2); /** * @fn ~KinematicsParams * @brief Destructor @@ -54,7 +54,7 @@ class KinematicsParams { } /** * @fn SetMass_kg - * @brief Set mass of the satellite + * @brief Set mass_kg of the satellite * @param [in] mass_kg: Mass of the satellite [kg] */ inline void SetMass_kg(const double mass_kg) { @@ -62,9 +62,9 @@ class KinematicsParams { } /** * @fn AddMass_kg - * @brief Add mass of the satellite + * @brief Add mass_kg of the satellite * @param [in] mass_kg: Mass of the satellite [kg] - * @note Normally, this function is used to decrease the mass due to the fuel consumption. + * @note Normally, this function is used to decrease the mass_kg due to the fuel consumption. */ inline void AddMass_kg(const double mass_kg) { double temp_mass_kg = mass_kg_ + mass_kg; From c5389b713435c60acbe08f2d3a510a4f46ec95a4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:49:41 +0100 Subject: [PATCH 0889/1086] Fix class name --- .../spacecraft/structure/initialize_structure.cpp | 4 ++-- .../spacecraft/structure/initialize_structure.hpp | 2 +- .../spacecraft/structure/kinematics_parameters.cpp | 2 +- .../spacecraft/structure/kinematics_parameters.hpp | 12 ++++++------ src/simulation/spacecraft/structure/structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.hpp | 10 +++++----- 6 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index bf9191fd2..600453723 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -9,7 +9,7 @@ #include #define MIN_VAL 1e-6 -KinematicsParams InitKinematicsParams(std::string ini_path) { +KinematicsParameters InitKinematicsParams(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "KINEMATIC_PARAMETERS"; @@ -25,7 +25,7 @@ KinematicsParams InitKinematicsParams(std::string ini_path) { } } - KinematicsParams kinematics_params(center_of_gravity_b_m, mass_kg, inertia_tensor_b_kgm2); + KinematicsParameters kinematics_params(center_of_gravity_b_m, mass_kg, inertia_tensor_b_kgm2); return kinematics_params; } diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index e890d1992..5be44cccb 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -14,7 +14,7 @@ * @fn InitKinematicsParams * @brief Initialize the kinematics parameters with an ini file */ -KinematicsParams InitKinematicsParams(std::string ini_path); +KinematicsParameters InitKinematicsParams(std::string ini_path); /** * @fn InitSurfaces * @brief Initialize the multiple surfaces with an ini file diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.cpp b/src/simulation/spacecraft/structure/kinematics_parameters.cpp index e1cfc572d..bd2cc3346 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.cpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.cpp @@ -5,5 +5,5 @@ #include "kinematics_parameters.hpp" -KinematicsParams::KinematicsParams(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2) +KinematicsParameters::KinematicsParameters(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2) : center_of_gravity_b_m_(center_of_gravity_b_m), mass_kg_(mass_kg), inertia_tensor_b_kgm2_(inertia_tensor_b_kgm2) {} \ No newline at end of file diff --git a/src/simulation/spacecraft/structure/kinematics_parameters.hpp b/src/simulation/spacecraft/structure/kinematics_parameters.hpp index a2957455c..2246dcd63 100644 --- a/src/simulation/spacecraft/structure/kinematics_parameters.hpp +++ b/src/simulation/spacecraft/structure/kinematics_parameters.hpp @@ -10,21 +10,21 @@ #include /** - * @class KinematicsParams + * @class KinematicsParameters * @brief Class for spacecraft Kinematics information */ -class KinematicsParams { +class KinematicsParameters { public: /** - * @fn KinematicsParams + * @fn KinematicsParameters * @brief Constructor */ - KinematicsParams(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2); + KinematicsParameters(libra::Vector<3> center_of_gravity_b_m, double mass_kg, libra::Matrix<3, 3> inertia_tensor_b_kgm2); /** - * @fn ~KinematicsParams + * @fn ~KinematicsParameters * @brief Destructor */ - ~KinematicsParams(){}; + ~KinematicsParameters(){}; // Getter /** diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index f6e89ab50..7121ce22c 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -22,7 +22,7 @@ void Structure::Initialize(SimulationConfig* simulation_configuration, const int // Save ini file simulation_configuration->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize - kinnematics_params_ = new KinematicsParams(InitKinematicsParams(ini_fname)); + kinnematics_params_ = new KinematicsParameters(InitKinematicsParams(ini_fname)); surfaces_ = InitSurfaces(ini_fname); rmm_params_ = new RMMParams(InitRMMParams(ini_fname)); } diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index d6cd4484c..497f27562 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -46,7 +46,7 @@ class Structure { * @fn GetKinematicsParams * @brief Return kinematics information */ - inline const KinematicsParams& GetKinematicsParams() const { return *kinnematics_params_; } + inline const KinematicsParameters& GetKinematicsParams() const { return *kinnematics_params_; } /** * @fn GetRMMParams * @brief Return Residual Magnetic Moment information @@ -62,7 +62,7 @@ class Structure { * @fn GetToSetKinematicsParams * @brief Return kinematics information */ - inline KinematicsParams& GetToSetKinematicsParams() { return *kinnematics_params_; } + inline KinematicsParameters& GetToSetKinematicsParams() { return *kinnematics_params_; } /** * @fn GetToSetRMMParams * @brief Return Residual Magnetic Moment information @@ -70,9 +70,9 @@ class Structure { inline RMMParams& GetToSetRMMParams() { return *rmm_params_; } private: - KinematicsParams* kinnematics_params_; //!< Kinematics parameters - vector surfaces_; //!< Surface information - RMMParams* rmm_params_; //!< Residual Magnetic Moment + KinematicsParameters* kinnematics_params_; //!< Kinematics parameters + vector surfaces_; //!< Surface information + RMMParams* rmm_params_; //!< Residual Magnetic Moment }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ From ced126ab94040ebc12a08f51569050103ba5f5b6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:51:41 +0100 Subject: [PATCH 0890/1086] Fix private variables name --- .../structure/residual_magnetic_moment.cpp | 5 ++++- .../structure/residual_magnetic_moment.hpp | 20 +++++++++---------- 2 files changed, 14 insertions(+), 11 deletions(-) diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp index 365379d38..60be724d7 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp @@ -6,4 +6,7 @@ #include "residual_magnetic_moment.hpp" RMMParams::RMMParams(Vector<3> rmm_const_b, double rmm_rwdev, double rmm_rwlimit, double rmm_wnvar) - : rmm_const_b_(rmm_const_b), rmm_rwdev_(rmm_rwdev), rmm_rwlimit_(rmm_rwlimit), rmm_wnvar_(rmm_wnvar) {} + : constant_value_b_Am2_(rmm_const_b), + random_walk_standard_deviation_Am2(rmm_rwdev), + random_walk_limit_Am2(rmm_rwlimit), + random_noise_standard_deviation_Am2(rmm_wnvar) {} diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 0f2979450..c0ceed5d8 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -31,22 +31,22 @@ class RMMParams { * @fn GetRMMConst_b * @brief Return Constant value of RMM at body frame [Am2] */ - inline const Vector<3>& GetRMMConst_b(void) const { return rmm_const_b_; } + inline const Vector<3>& GetRMMConst_b(void) const { return constant_value_b_Am2_; } /** * @fn GetRMMRWDev * @brief Return Random walk standard deviation of RMM [Am2] */ - inline const double& GetRMMRWDev(void) const { return rmm_rwdev_; } + inline const double& GetRMMRWDev(void) const { return random_walk_standard_deviation_Am2; } /** * @fn GetRMMRWDev * @brief Random walk limit of RMM [Am2] */ - inline const double& GetRMMRWLimit(void) const { return rmm_rwlimit_; } + inline const double& GetRMMRWLimit(void) const { return random_walk_limit_Am2; } /** * @fn GetRMMRWDev * @brief Standard deviation of white noise of RMM [Am2] */ - inline const double& GetRMMWNVar(void) const { return rmm_wnvar_; } + inline const double& GetRMMWNVar(void) const { return random_noise_standard_deviation_Am2; } // Setter /** @@ -54,19 +54,19 @@ class RMMParams { * @brief Set Constant value of RMM at body frame [Am2] * @param [in] rmm_const_b_Am2: Constant value of RMM at the body frame [Am2] */ - inline void SetRmmConstant_b_Am2(const Vector<3> rmm_const_b_Am2) { rmm_const_b_ = rmm_const_b_Am2; } + inline void SetRmmConstant_b_Am2(const Vector<3> rmm_const_b_Am2) { constant_value_b_Am2_ = rmm_const_b_Am2; } /** * @fn AddRMMConst_b_Am2 * @brief Add Constant value of RMM at body frame [Am2] * @param [in] rmm_const_b_Am2: Constant value of RMM at the body frame [Am2] */ - inline void AddRmmConstant_b_Am2(const Vector<3> rmm_const_b_Am2) { rmm_const_b_ += rmm_const_b_Am2; } + inline void AddRmmConstant_b_Am2(const Vector<3> rmm_const_b_Am2) { constant_value_b_Am2_ += rmm_const_b_Am2; } private: - Vector<3> rmm_const_b_; //!< Constant value of RMM at body frame [Am2] - double rmm_rwdev_; //!< Random walk standard deviation of RMM [Am2] - double rmm_rwlimit_; //!< Random walk limit of RMM [Am2] - double rmm_wnvar_; //!< Standard deviation of white noise of RMM [Am2] + Vector<3> constant_value_b_Am2_; //!< Constant value of RMM at body frame [Am2] + double random_walk_standard_deviation_Am2; //!< Random walk standard deviation of RMM [Am2] + double random_walk_limit_Am2; //!< Random walk limit of RMM [Am2] + double random_noise_standard_deviation_Am2; //!< Standard deviation of white noise of RMM [Am2] }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_HPP_ \ No newline at end of file From b773f5ff556c417fa5af8e26d8b21b6e1f0c9e0b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:55:01 +0100 Subject: [PATCH 0891/1086] Fix private variables name --- .../structure/initialize_structure.cpp | 6 +++--- .../structure/residual_magnetic_moment.cpp | 11 ++++++----- .../structure/residual_magnetic_moment.hpp | 17 +++++++++-------- 3 files changed, 18 insertions(+), 16 deletions(-) diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 600453723..242a58ad8 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -113,9 +113,9 @@ RMMParams InitRMMParams(std::string ini_path) { libra::Vector<3> rmm_const_b; conf.ReadVector(section, "rmm_constant_b_Am2", rmm_const_b); double rmm_rwdev = conf.ReadDouble(section, "rmm_random_walk_speed_Am2"); - double rmm_rwlimit = conf.ReadDouble(section, "rmm_random_walk_limit_Am2"); - double rmm_wnvar = conf.ReadDouble(section, "rmm_white_noise_standard_deviation_Am2"); + double random_walk_limit_Am2 = conf.ReadDouble(section, "rmm_random_walk_limit_Am2"); + double random_noise_standard_deviation_Am2 = conf.ReadDouble(section, "rmm_white_noise_standard_deviation_Am2"); - RMMParams rmm_params(rmm_const_b, rmm_rwdev, rmm_rwlimit, rmm_wnvar); + RMMParams rmm_params(rmm_const_b, rmm_rwdev, random_walk_limit_Am2, random_noise_standard_deviation_Am2); return rmm_params; } diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp index 60be724d7..47cda0fd2 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp @@ -5,8 +5,9 @@ #include "residual_magnetic_moment.hpp" -RMMParams::RMMParams(Vector<3> rmm_const_b, double rmm_rwdev, double rmm_rwlimit, double rmm_wnvar) - : constant_value_b_Am2_(rmm_const_b), - random_walk_standard_deviation_Am2(rmm_rwdev), - random_walk_limit_Am2(rmm_rwlimit), - random_noise_standard_deviation_Am2(rmm_wnvar) {} +RMMParams::RMMParams(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, const double random_walk_limit_Am2, + const double random_noise_standard_deviation_Am2) + : constant_value_b_Am2_(constant_value_b_Am2_), + random_walk_standard_deviation_Am2_(random_walk_standard_deviation_Am2), + random_walk_limit_Am2_(random_walk_limit_Am2), + random_noise_standard_deviation_Am2_(random_noise_standard_deviation_Am2) {} diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index c0ceed5d8..9f184d5d3 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -19,7 +19,8 @@ class RMMParams { * @fn RMMParams * @brief Constructor */ - RMMParams(Vector<3> rmm_const_b, double rmm_rwdev, double rmm_rwlimit, double rmm_wnvar); + RMMParams(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, const double random_walk_limit_Am2, + const double random_noise_standard_deviation_Am2); /** * @fn ~RMMParams * @brief Destructor @@ -36,17 +37,17 @@ class RMMParams { * @fn GetRMMRWDev * @brief Return Random walk standard deviation of RMM [Am2] */ - inline const double& GetRMMRWDev(void) const { return random_walk_standard_deviation_Am2; } + inline const double& GetRMMRWDev(void) const { return random_walk_standard_deviation_Am2_; } /** * @fn GetRMMRWDev * @brief Random walk limit of RMM [Am2] */ - inline const double& GetRMMRWLimit(void) const { return random_walk_limit_Am2; } + inline const double& GetRMMRWLimit(void) const { return random_walk_limit_Am2_; } /** * @fn GetRMMRWDev * @brief Standard deviation of white noise of RMM [Am2] */ - inline const double& GetRMMWNVar(void) const { return random_noise_standard_deviation_Am2; } + inline const double& GetRMMWNVar(void) const { return random_noise_standard_deviation_Am2_; } // Setter /** @@ -63,10 +64,10 @@ class RMMParams { inline void AddRmmConstant_b_Am2(const Vector<3> rmm_const_b_Am2) { constant_value_b_Am2_ += rmm_const_b_Am2; } private: - Vector<3> constant_value_b_Am2_; //!< Constant value of RMM at body frame [Am2] - double random_walk_standard_deviation_Am2; //!< Random walk standard deviation of RMM [Am2] - double random_walk_limit_Am2; //!< Random walk limit of RMM [Am2] - double random_noise_standard_deviation_Am2; //!< Standard deviation of white noise of RMM [Am2] + Vector<3> constant_value_b_Am2_; //!< Constant value of RMM at body frame [Am2] + double random_walk_standard_deviation_Am2_; //!< Random walk standard deviation of RMM [Am2] + double random_walk_limit_Am2_; //!< Random walk limit of RMM [Am2] + double random_noise_standard_deviation_Am2_; //!< Standard deviation of white noise of RMM [Am2] }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_RESIDUAL_MAGNETIC_MOMENT_HPP_ \ No newline at end of file From 6d3c0c1640f2e4e1b86daedc876df9660b10344f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:57:49 +0100 Subject: [PATCH 0892/1086] Fix public function name --- src/disturbances/magnetic_disturbance.cpp | 10 +++++----- .../structure/residual_magnetic_moment.hpp | 16 ++++++++-------- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 5a62551c9..e447efe9a 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -14,7 +14,7 @@ MagneticDisturbance::MagneticDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { - rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); + rmm_b_Am2_ = rmm_params_.GetConstantValue_b_Am2(); } Vector<3> MagneticDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { @@ -30,12 +30,12 @@ void MagneticDisturbance::Update(const LocalEnvironment& local_environment, cons } void MagneticDisturbance::CalcRMM() { - static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRMMRWDev()); - static libra::Vector<3> random_walk_limit(rmm_params_.GetRMMRWLimit()); + static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRandomWalkStandardDeviation_Am2()); + static libra::Vector<3> random_walk_limit(rmm_params_.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, rmm_params_.GetRMMWNVar(), global_randomization.MakeSeed()); + static libra::NormalRand normal_random(0.0, rmm_params_.GetRandomNoiseStandardDeviation_Am2(), global_randomization.MakeSeed()); - rmm_b_Am2_ = rmm_params_.GetRMMConst_b(); + rmm_b_Am2_ = rmm_params_.GetConstantValue_b_Am2(); for (int i = 0; i < 3; ++i) { rmm_b_Am2_[i] += random_walk[i] + normal_random; } diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 9f184d5d3..1a204b768 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -29,25 +29,25 @@ class RMMParams { // Getter /** - * @fn GetRMMConst_b + * @fn GetConstantValue_b_Am2 * @brief Return Constant value of RMM at body frame [Am2] */ - inline const Vector<3>& GetRMMConst_b(void) const { return constant_value_b_Am2_; } + inline const Vector<3>& GetConstantValue_b_Am2(void) const { return constant_value_b_Am2_; } /** - * @fn GetRMMRWDev + * @fn GetRandomWalkStandardDeviation_Am2 * @brief Return Random walk standard deviation of RMM [Am2] */ - inline const double& GetRMMRWDev(void) const { return random_walk_standard_deviation_Am2_; } + inline const double& GetRandomWalkStandardDeviation_Am2(void) const { return random_walk_standard_deviation_Am2_; } /** - * @fn GetRMMRWDev + * @fn GetRandomWalkLimit_Am2 * @brief Random walk limit of RMM [Am2] */ - inline const double& GetRMMRWLimit(void) const { return random_walk_limit_Am2_; } + inline const double& GetRandomWalkLimit_Am2(void) const { return random_walk_limit_Am2_; } /** - * @fn GetRMMRWDev + * @fn GetRandomNoiseStandardDeviation_Am2 * @brief Standard deviation of white noise of RMM [Am2] */ - inline const double& GetRMMWNVar(void) const { return random_noise_standard_deviation_Am2_; } + inline const double& GetRandomNoiseStandardDeviation_Am2(void) const { return random_noise_standard_deviation_Am2_; } // Setter /** From f127ab9cff45dbcb59963631cac530bba282950d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:58:37 +0100 Subject: [PATCH 0893/1086] Rename class --- src/disturbances/initialize_disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.hpp | 2 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 6 +++--- .../spacecraft/structure/initialize_structure.cpp | 4 ++-- .../spacecraft/structure/initialize_structure.hpp | 2 +- .../structure/residual_magnetic_moment.cpp | 4 ++-- .../structure/residual_magnetic_moment.hpp | 14 +++++++------- src/simulation/spacecraft/structure/structure.cpp | 2 +- src/simulation/spacecraft/structure/structure.hpp | 6 +++--- 10 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 66fc74798..75561e730 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -63,7 +63,7 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons return gg_disturbance; } -MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params) { +MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const ResidualMagneticMoment& rmm_params) { auto conf = IniAccess(initialize_file_path); const char* section = "MAGNETIC_DISTURBANCE"; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index e5fea9d90..bd37f1a90 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -53,7 +53,7 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons * @param [in] initialize_file_path: Initialize file path * @param [in] rmm_params: RMM parameters */ -MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const RMMParams& rmm_params); +MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const ResidualMagneticMoment& rmm_params); /** * @fn InitGeoPotential diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index e447efe9a..6104609d0 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -12,7 +12,7 @@ #include "../library/randomization/normal_randomization.hpp" #include "../library/randomization/random_walk.hpp" -MagneticDisturbance::MagneticDisturbance(const RMMParams& rmm_params, const bool is_calculation_enabled) +MagneticDisturbance::MagneticDisturbance(const ResidualMagneticMoment& rmm_params, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { rmm_b_Am2_ = rmm_params_.GetConstantValue_b_Am2(); } diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index e623a948c..997e274f3 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -25,7 +25,7 @@ class MagneticDisturbance : public SimpleDisturbance { * @param [in] rmm_parameters: RMM parameters of the spacecraft * @param [in] is_calculation_enabled: Calculation flag */ - MagneticDisturbance(const RMMParams& rmm_parameters, const bool is_calculation_enabled = true); + MagneticDisturbance(const ResidualMagneticMoment& rmm_parameters, const bool is_calculation_enabled = true); /** * @fn Update @@ -50,8 +50,8 @@ class MagneticDisturbance : public SimpleDisturbance { private: const double kMagUnit_ = 1.0e-9; //!< Constant value to change the unit [nT] -> [T] - libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] - const RMMParams& rmm_params_; //!< RMM parameters + libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] + const ResidualMagneticMoment& rmm_params_; //!< RMM parameters /** * @fn CalcRMM diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 242a58ad8..e6265a95a 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -106,7 +106,7 @@ vector InitSurfaces(std::string ini_path) { return surfaces; } -RMMParams InitRMMParams(std::string ini_path) { +ResidualMagneticMoment InitRMMParams(std::string ini_path) { auto conf = IniAccess(ini_path); const char* section = "RESIDUAL_MAGNETIC_MOMENT"; @@ -116,6 +116,6 @@ RMMParams InitRMMParams(std::string ini_path) { double random_walk_limit_Am2 = conf.ReadDouble(section, "rmm_random_walk_limit_Am2"); double random_noise_standard_deviation_Am2 = conf.ReadDouble(section, "rmm_white_noise_standard_deviation_Am2"); - RMMParams rmm_params(rmm_const_b, rmm_rwdev, random_walk_limit_Am2, random_noise_standard_deviation_Am2); + ResidualMagneticMoment rmm_params(rmm_const_b, rmm_rwdev, random_walk_limit_Am2, random_noise_standard_deviation_Am2); return rmm_params; } diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index 5be44cccb..6b49d23e6 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -24,6 +24,6 @@ vector InitSurfaces(std::string ini_path); * @fn InitRMMParams * @brief Initialize the RMM(Residual Magnetic Moment) parameters with an ini file */ -RMMParams InitRMMParams(std::string ini_path); +ResidualMagneticMoment InitRMMParams(std::string ini_path); #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_HPP_ diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp index 47cda0fd2..0fe90e09f 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.cpp @@ -5,8 +5,8 @@ #include "residual_magnetic_moment.hpp" -RMMParams::RMMParams(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, const double random_walk_limit_Am2, - const double random_noise_standard_deviation_Am2) +ResidualMagneticMoment::ResidualMagneticMoment(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, + const double random_walk_limit_Am2, const double random_noise_standard_deviation_Am2) : constant_value_b_Am2_(constant_value_b_Am2_), random_walk_standard_deviation_Am2_(random_walk_standard_deviation_Am2), random_walk_limit_Am2_(random_walk_limit_Am2), diff --git a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp index 1a204b768..e12ecc4dd 100644 --- a/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp +++ b/src/simulation/spacecraft/structure/residual_magnetic_moment.hpp @@ -10,22 +10,22 @@ using libra::Vector; /** - * @class RMMParams + * @class ResidualMagneticMoment * @brief Class for spacecraft RMM (Residual Magnetic Moment) */ -class RMMParams { +class ResidualMagneticMoment { public: /** - * @fn RMMParams + * @fn ResidualMagneticMoment * @brief Constructor */ - RMMParams(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, const double random_walk_limit_Am2, - const double random_noise_standard_deviation_Am2); + ResidualMagneticMoment(const Vector<3> constant_value_b_Am2_, const double random_walk_standard_deviation_Am2, const double random_walk_limit_Am2, + const double random_noise_standard_deviation_Am2); /** - * @fn ~RMMParams + * @fn ~ResidualMagneticMoment * @brief Destructor */ - ~RMMParams(){}; + ~ResidualMagneticMoment(){}; // Getter /** diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 7121ce22c..0938f08c3 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -24,5 +24,5 @@ void Structure::Initialize(SimulationConfig* simulation_configuration, const int // Initialize kinnematics_params_ = new KinematicsParameters(InitKinematicsParams(ini_fname)); surfaces_ = InitSurfaces(ini_fname); - rmm_params_ = new RMMParams(InitRMMParams(ini_fname)); + rmm_params_ = new ResidualMagneticMoment(InitRMMParams(ini_fname)); } diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 497f27562..5c616e388 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -51,7 +51,7 @@ class Structure { * @fn GetRMMParams * @brief Return Residual Magnetic Moment information */ - inline const RMMParams& GetRMMParams() const { return *rmm_params_; } + inline const ResidualMagneticMoment& GetRMMParams() const { return *rmm_params_; } /** * @fn GetToSetSurfaces @@ -67,12 +67,12 @@ class Structure { * @fn GetToSetRMMParams * @brief Return Residual Magnetic Moment information */ - inline RMMParams& GetToSetRMMParams() { return *rmm_params_; } + inline ResidualMagneticMoment& GetToSetRMMParams() { return *rmm_params_; } private: KinematicsParameters* kinnematics_params_; //!< Kinematics parameters vector surfaces_; //!< Surface information - RMMParams* rmm_params_; //!< Residual Magnetic Moment + ResidualMagneticMoment* rmm_params_; //!< Residual Magnetic Moment }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ From 8a3d743aabc939d1b6530bd12688be9c0b6046e4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 14:59:59 +0100 Subject: [PATCH 0894/1086] Fix private variables --- .../spacecraft/structure/surface.cpp | 7 ++++++- .../spacecraft/structure/surface.hpp | 20 +++++++++---------- 2 files changed, 16 insertions(+), 11 deletions(-) diff --git a/src/simulation/spacecraft/structure/surface.cpp b/src/simulation/spacecraft/structure/surface.cpp index 55d96b9d0..4dce0e31e 100644 --- a/src/simulation/spacecraft/structure/surface.cpp +++ b/src/simulation/spacecraft/structure/surface.cpp @@ -6,4 +6,9 @@ #include "surface.hpp" Surface::Surface(Vector<3> position, Vector<3> normal, double area, double reflectivity, double specularity, double air_specularity) - : position_(position), normal_(normal), area_(area), reflectivity_(reflectivity), specularity_(specularity), air_specularity_(air_specularity) {} + : position_b_m_(position), + normal_b_(normal), + area_m2_(area), + reflectivity_(reflectivity), + specularity_(specularity), + air_specularity_(air_specularity) {} diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 87821cd99..1c3f525a4 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -31,17 +31,17 @@ class Surface { * @fn GetPosition * @brief Return position vector of geometric center of the surface in body frame and meter unit */ - inline const Vector<3>& GetPosition(void) const { return position_; } + inline const Vector<3>& GetPosition(void) const { return position_b_m_; } /** * @fn GetNormal * @brief Return normal vector of the surface in body frame */ - inline const Vector<3>& GetNormal(void) const { return normal_; } + inline const Vector<3>& GetNormal(void) const { return normal_b_; } /** * @fn GetArea * @brief Return area of the surface in meter^2 unit */ - inline const double& GetArea(void) const { return area_; } + inline const double& GetArea(void) const { return area_m2_; } /** * @fn GetReflectivity * @brief Return reflectivity of the surface @@ -64,15 +64,15 @@ class Surface { * @brief Set position vector of geometric center of the surface in body frame [m] * @param[in] position_b_m: Position vector of geometric center of the surface in body frame [m] */ - inline void SetPosition_b_m(const Vector<3> position_b_m) { position_ = position_b_m; } + inline void SetPosition_b_m(const Vector<3> position_b_m) { position_b_m_ = position_b_m; } /** * @fn SetNormal * @brief Set normal vector of the surface in body frame * @param[in] normal_b: Normal vector of the surface in body frame */ inline void SetNormal_b(const Vector<3> normal_b) { - normal_ = normal_b; - normal_ = Normalize(normal_); + normal_b_ = normal_b; + normal_b_ = Normalize(normal_b_); } /** * @fn SetArea @@ -80,7 +80,7 @@ class Surface { * @param[in] area_m2: Area of the surface [m2] */ inline void SetArea(const double area_m2) { - if (area_m2 > 0.0) area_ = area_m2; + if (area_m2 > 0.0) area_m2_ = area_m2; } /** * @fn SetReflectivity @@ -108,9 +108,9 @@ class Surface { } private: - Vector<3> position_; //!< Position vector of the surface @ Body Frame [m] - Vector<3> normal_; //!< Normal unit vector of the surface @ Body Frame [-] - double area_; //!< Area of the surface [m2] + Vector<3> position_b_m_; //!< Position vector of the surface @ Body Frame [m] + Vector<3> normal_b_; //!< Normal unit vector of the surface @ Body Frame [-] + double area_m2_; //!< Area of the surface [m2] double reflectivity_; //!< Total reflectivity for solar wavelength (1.0 - solar absorption) double specularity_; //!< Ratio of specular reflection in the total reflected light double air_specularity_; //!< Specularity for air drag From a76a9854fb05c732171c940b245247c6e089e587 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:02:08 +0100 Subject: [PATCH 0895/1086] Fix function argument names --- src/simulation/spacecraft/structure/surface.cpp | 9 +++++---- src/simulation/spacecraft/structure/surface.hpp | 3 ++- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/simulation/spacecraft/structure/surface.cpp b/src/simulation/spacecraft/structure/surface.cpp index 4dce0e31e..2666526e2 100644 --- a/src/simulation/spacecraft/structure/surface.cpp +++ b/src/simulation/spacecraft/structure/surface.cpp @@ -5,10 +5,11 @@ #include "surface.hpp" -Surface::Surface(Vector<3> position, Vector<3> normal, double area, double reflectivity, double specularity, double air_specularity) - : position_b_m_(position), - normal_b_(normal), - area_m2_(area), +Surface::Surface(const libra::Vector<3> position_b_m, const libra::Vector<3> normal_b, const double area_m2, const double reflectivity, + const double specularity, const double air_specularity) + : position_b_m_(position_b_m), + normal_b_(normal_b), + area_m2_(area_m2), reflectivity_(reflectivity), specularity_(specularity), air_specularity_(air_specularity) {} diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 1c3f525a4..79302a9ab 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -19,7 +19,8 @@ class Surface { * @fn Surface * @brief Constructor */ - Surface(Vector<3> position, Vector<3> normal, double area, double reflectivity, double specularity, double air_specularity); + Surface(const libra::Vector<3> position_b_m, const libra::Vector<3> normal_b, const double area_m2, const double reflectivity, + const double specularity, const double air_specularity); /** * @fn ~Surface * @brief Destructor From 042576747a9c545aad27a0dfcf36c19f44d3e3c8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:02:50 +0100 Subject: [PATCH 0896/1086] Remove using --- .../spacecraft/structure/surface.hpp | 21 +++++++++---------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index 79302a9ab..f89be3f86 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -7,7 +7,6 @@ #define S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_HPP_ #include -using libra::Vector; /** * @class Surface @@ -32,12 +31,12 @@ class Surface { * @fn GetPosition * @brief Return position vector of geometric center of the surface in body frame and meter unit */ - inline const Vector<3>& GetPosition(void) const { return position_b_m_; } + inline const libra::Vector<3>& GetPosition(void) const { return position_b_m_; } /** * @fn GetNormal * @brief Return normal vector of the surface in body frame */ - inline const Vector<3>& GetNormal(void) const { return normal_b_; } + inline const libra::Vector<3>& GetNormal(void) const { return normal_b_; } /** * @fn GetArea * @brief Return area of the surface in meter^2 unit @@ -65,13 +64,13 @@ class Surface { * @brief Set position vector of geometric center of the surface in body frame [m] * @param[in] position_b_m: Position vector of geometric center of the surface in body frame [m] */ - inline void SetPosition_b_m(const Vector<3> position_b_m) { position_b_m_ = position_b_m; } + inline void SetPosition_b_m(const libra::Vector<3> position_b_m) { position_b_m_ = position_b_m; } /** * @fn SetNormal * @brief Set normal vector of the surface in body frame * @param[in] normal_b: Normal vector of the surface in body frame */ - inline void SetNormal_b(const Vector<3> normal_b) { + inline void SetNormal_b(const libra::Vector<3> normal_b) { normal_b_ = normal_b; normal_b_ = Normalize(normal_b_); } @@ -109,12 +108,12 @@ class Surface { } private: - Vector<3> position_b_m_; //!< Position vector of the surface @ Body Frame [m] - Vector<3> normal_b_; //!< Normal unit vector of the surface @ Body Frame [-] - double area_m2_; //!< Area of the surface [m2] - double reflectivity_; //!< Total reflectivity for solar wavelength (1.0 - solar absorption) - double specularity_; //!< Ratio of specular reflection in the total reflected light - double air_specularity_; //!< Specularity for air drag + libra::Vector<3> position_b_m_; //!< Position vector of the surface @ Body Frame [m] + libra::Vector<3> normal_b_; //!< Normal unit vector of the surface @ Body Frame [-] + double area_m2_; //!< Area of the surface [m2] + double reflectivity_; //!< Total reflectivity for solar wavelength (1.0 - solar absorption) + double specularity_; //!< Ratio of specular reflection in the total reflected light + double air_specularity_; //!< Specularity for air drag }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_SURFACE_HPP_ From 921774c2f113840025be348fc3d3d02174687c19 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:04:13 +0100 Subject: [PATCH 0897/1086] Fix public function name --- .../examples/example_change_structure.cpp | 2 +- src/disturbances/air_drag.cpp | 2 +- .../solar_radiation_pressure_disturbance.cpp | 2 +- src/disturbances/surface_force.cpp | 6 +++--- src/simulation/spacecraft/structure/surface.hpp | 16 ++++++++-------- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/components/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp index f5c17b52b..61e5414bb 100644 --- a/src/components/examples/example_change_structure.cpp +++ b/src/components/examples/example_change_structure.cpp @@ -27,7 +27,7 @@ void ExampleChangeStructure::MainRoutine(const int time_count) { rmm[2] = 0.2; structure_->GetToSetRMMParams().SetRmmConstant_b_Am2(rmm); // Surface - structure_->GetToSetSurfaces()[0].SetArea(0.5); + structure_->GetToSetSurfaces()[0].SetArea_m2(0.5); } } diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 7d67ac9dc..107d901c3 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -32,7 +32,7 @@ void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const dou double velocity_norm_m_s = CalcNorm(velocity_b_m_s); CalcCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { - double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea(); + double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea_m2(); normal_coefficients_[i] = k * cn_[i]; tangential_coefficients_[i] = k * ct_[i]; } diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index 29980dccb..c34da9989 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -24,7 +24,7 @@ void SolarRadiationPressureDisturbance::CalcCoefficients(const libra::Vector<3>& UNUSED(input_direction_b); for (size_t i = 0; i < surfaces_.size(); i++) { // Calculate for each surface - double area = surfaces_[i].GetArea(); + double area = surfaces_[i].GetArea_m2(); double reflectivity = surfaces_[i].GetReflectivity(); double specularity = surfaces_[i].GetSpecularity(); normal_coefficients_[i] = diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 19a213297..1b8858d58 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -29,7 +29,7 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction for (size_t i = 0; i < surfaces_.size(); i++) { if (cos_theta_[i] > 0.0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force - libra::Vector<3> normal = surfaces_[i].GetNormal(); + libra::Vector<3> normal = surfaces_[i].GetNormal_b(); libra::Vector<3> ncu = OuterProduct(input_b_normal, normal); libra::Vector<3> ncu_normalized = Normalize(ncu); libra::Vector<3> in_plane_force_direction = OuterProduct(ncu_normalized, normal); @@ -37,7 +37,7 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction libra::Vector<3> force_per_surface_b_N = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * in_plane_force_direction; force_b_N += force_per_surface_b_N; // calc torque - torque_b_Nm += OuterProduct(surfaces_[i].GetPosition() - center_of_gravity_b_m_, force_per_surface_b_N); + torque_b_Nm += OuterProduct(surfaces_[i].GetPosition_b_m() - center_of_gravity_b_m_, force_per_surface_b_N); } } force_b_N_ = force_b_N; @@ -50,7 +50,7 @@ void SurfaceForce::CalcTheta(libra::Vector<3>& input_direction_b) { Normalize(input_b_normal); for (size_t i = 0; i < surfaces_.size(); i++) { - cos_theta_[i] = InnerProduct(surfaces_[i].GetNormal(), input_b_normal); + cos_theta_[i] = InnerProduct(surfaces_[i].GetNormal_b(), input_b_normal); sin_theta_[i] = sqrt(1.0 - cos_theta_[i] * cos_theta_[i]); } } diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index f89be3f86..a2837cfa1 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -28,20 +28,20 @@ class Surface { // Getter /** - * @fn GetPosition + * @fn GetPosition_b_m * @brief Return position vector of geometric center of the surface in body frame and meter unit */ - inline const libra::Vector<3>& GetPosition(void) const { return position_b_m_; } + inline const libra::Vector<3>& GetPosition_b_m(void) const { return position_b_m_; } /** - * @fn GetNormal + * @fn GetNormal_b * @brief Return normal vector of the surface in body frame */ - inline const libra::Vector<3>& GetNormal(void) const { return normal_b_; } + inline const libra::Vector<3>& GetNormal_b(void) const { return normal_b_; } /** - * @fn GetArea + * @fn GetArea_m2 * @brief Return area of the surface in meter^2 unit */ - inline const double& GetArea(void) const { return area_m2_; } + inline const double& GetArea_m2(void) const { return area_m2_; } /** * @fn GetReflectivity * @brief Return reflectivity of the surface @@ -75,11 +75,11 @@ class Surface { normal_b_ = Normalize(normal_b_); } /** - * @fn SetArea + * @fn SetArea_m2 * @brief Set area of the surface * @param[in] area_m2: Area of the surface [m2] */ - inline void SetArea(const double area_m2) { + inline void SetArea_m2(const double area_m2) { if (area_m2 > 0.0) area_m2_ = area_m2; } /** From bd5fa16fc1649f1cdc394f73c0a27208861a0a23 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:05:23 +0100 Subject: [PATCH 0898/1086] Fix private variables name --- src/disturbances/magnetic_disturbance.cpp | 12 ++++++------ src/disturbances/magnetic_disturbance.hpp | 4 ++-- src/simulation/spacecraft/structure/structure.cpp | 8 ++++---- src/simulation/spacecraft/structure/structure.hpp | 14 +++++++------- 4 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 6104609d0..c61600e7f 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -13,8 +13,8 @@ #include "../library/randomization/random_walk.hpp" MagneticDisturbance::MagneticDisturbance(const ResidualMagneticMoment& rmm_params, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), rmm_params_(rmm_params) { - rmm_b_Am2_ = rmm_params_.GetConstantValue_b_Am2(); + : SimpleDisturbance(is_calculation_enabled), residual_magnetic_moment_(rmm_params) { + rmm_b_Am2_ = residual_magnetic_moment_.GetConstantValue_b_Am2(); } Vector<3> MagneticDisturbance::CalcTorque_b_Nm(const Vector<3>& magnetic_field_b_nT) { @@ -30,12 +30,12 @@ void MagneticDisturbance::Update(const LocalEnvironment& local_environment, cons } void MagneticDisturbance::CalcRMM() { - static libra::Vector<3> random_walk_std_dev(rmm_params_.GetRandomWalkStandardDeviation_Am2()); - static libra::Vector<3> random_walk_limit(rmm_params_.GetRandomWalkLimit_Am2()); + static libra::Vector<3> random_walk_std_dev(residual_magnetic_moment_.GetRandomWalkStandardDeviation_Am2()); + static libra::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, rmm_params_.GetRandomNoiseStandardDeviation_Am2(), global_randomization.MakeSeed()); + static libra::NormalRand normal_random(0.0, residual_magnetic_moment_.GetRandomNoiseStandardDeviation_Am2(), global_randomization.MakeSeed()); - rmm_b_Am2_ = rmm_params_.GetConstantValue_b_Am2(); + rmm_b_Am2_ = residual_magnetic_moment_.GetConstantValue_b_Am2(); for (int i = 0; i < 3; ++i) { rmm_b_Am2_[i] += random_walk[i] + normal_random; } diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 997e274f3..7a8f018ca 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -50,8 +50,8 @@ class MagneticDisturbance : public SimpleDisturbance { private: const double kMagUnit_ = 1.0e-9; //!< Constant value to change the unit [nT] -> [T] - libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] - const ResidualMagneticMoment& rmm_params_; //!< RMM parameters + libra::Vector<3> rmm_b_Am2_; //!< True RMM of the spacecraft in the body frame [Am2] + const ResidualMagneticMoment& residual_magnetic_moment_; //!< RMM parameters /** * @fn CalcRMM diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 0938f08c3..ca5256e75 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -11,8 +11,8 @@ Structure::Structure(SimulationConfig* simulation_configuration, const int spacecraft_id) { Initialize(simulation_configuration, spacecraft_id); } Structure::~Structure() { - delete kinnematics_params_; - delete rmm_params_; + delete kinematics_parameters_; + delete residual_magnetic_moment_; } void Structure::Initialize(SimulationConfig* simulation_configuration, const int spacecraft_id) { @@ -22,7 +22,7 @@ void Structure::Initialize(SimulationConfig* simulation_configuration, const int // Save ini file simulation_configuration->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize - kinnematics_params_ = new KinematicsParameters(InitKinematicsParams(ini_fname)); + kinematics_parameters_ = new KinematicsParameters(InitKinematicsParams(ini_fname)); surfaces_ = InitSurfaces(ini_fname); - rmm_params_ = new ResidualMagneticMoment(InitRMMParams(ini_fname)); + residual_magnetic_moment_ = new ResidualMagneticMoment(InitRMMParams(ini_fname)); } diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 5c616e388..2047a9c06 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -46,12 +46,12 @@ class Structure { * @fn GetKinematicsParams * @brief Return kinematics information */ - inline const KinematicsParameters& GetKinematicsParams() const { return *kinnematics_params_; } + inline const KinematicsParameters& GetKinematicsParams() const { return *kinematics_parameters_; } /** * @fn GetRMMParams * @brief Return Residual Magnetic Moment information */ - inline const ResidualMagneticMoment& GetRMMParams() const { return *rmm_params_; } + inline const ResidualMagneticMoment& GetRMMParams() const { return *residual_magnetic_moment_; } /** * @fn GetToSetSurfaces @@ -62,17 +62,17 @@ class Structure { * @fn GetToSetKinematicsParams * @brief Return kinematics information */ - inline KinematicsParameters& GetToSetKinematicsParams() { return *kinnematics_params_; } + inline KinematicsParameters& GetToSetKinematicsParams() { return *kinematics_parameters_; } /** * @fn GetToSetRMMParams * @brief Return Residual Magnetic Moment information */ - inline ResidualMagneticMoment& GetToSetRMMParams() { return *rmm_params_; } + inline ResidualMagneticMoment& GetToSetRMMParams() { return *residual_magnetic_moment_; } private: - KinematicsParameters* kinnematics_params_; //!< Kinematics parameters - vector surfaces_; //!< Surface information - ResidualMagneticMoment* rmm_params_; //!< Residual Magnetic Moment + KinematicsParameters* kinematics_parameters_; //!< Kinematics parameters + vector surfaces_; //!< Surface information + ResidualMagneticMoment* residual_magnetic_moment_; //!< Residual Magnetic Moment }; #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_STRUCTURE_HPP_ From bded6d2ceed2e958ec5ab0c8755a33b7e09a359d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:07:39 +0100 Subject: [PATCH 0899/1086] Fix public function name --- .../examples/example_change_structure.cpp | 6 +++--- .../real/propulsion/simple_thruster.cpp | 2 +- src/disturbances/disturbances.cpp | 6 +++--- src/dynamics/dynamics.cpp | 2 +- src/dynamics/dynamics.hpp | 2 +- .../spacecraft/structure/structure.cpp | 6 ++++-- .../spacecraft/structure/structure.hpp | 20 +++++++++---------- 7 files changed, 23 insertions(+), 21 deletions(-) diff --git a/src/components/examples/example_change_structure.cpp b/src/components/examples/example_change_structure.cpp index 61e5414bb..105b8ee5e 100644 --- a/src/components/examples/example_change_structure.cpp +++ b/src/components/examples/example_change_structure.cpp @@ -13,19 +13,19 @@ ExampleChangeStructure::~ExampleChangeStructure() {} void ExampleChangeStructure::MainRoutine(const int time_count) { if (time_count > 1000) { // Mass - structure_->GetToSetKinematicsParams().SetMass_kg(100.0); + structure_->GetToSetKinematicsParameters().SetMass_kg(100.0); // Center of gravity Vector<3> cg(0.0); cg[0] = 0.01; cg[1] = -0.01; cg[2] = 0.02; - structure_->GetToSetKinematicsParams().SetCenterOfGravityVector_b_m(cg); + structure_->GetToSetKinematicsParameters().SetCenterOfGravityVector_b_m(cg); // RMM Vector<3> rmm(0.0); rmm[0] = 0.1; rmm[1] = -0.1; rmm[2] = 0.2; - structure_->GetToSetRMMParams().SetRmmConstant_b_Am2(rmm); + structure_->GetToSetResidualMagneticMoment().SetRmmConstant_b_Am2(rmm); // Surface structure_->GetToSetSurfaces()[0].SetArea_m2(0.5); } diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index f82a54eff..4e5412ce3 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -50,7 +50,7 @@ void SimpleThruster::MainRoutine(const int time_count) { UNUSED(time_count); CalcThrust(); - CalcTorque(structure_->GetKinematicsParams().GetCenterOfGravity_b_m()); + CalcTorque(structure_->GetKinematicsParameters().GetCenterOfGravity_b_m()); } void SimpleThruster::PowerOffRoutine() { diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index ae8f345a9..25433880f 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -72,7 +72,7 @@ void Disturbances::InitializeInstances(const SimulationConfig* simulation_config disturbances_list_.push_back(gg_dist); SolarRadiationPressureDisturbance* srp_dist = new SolarRadiationPressureDisturbance(InitSolarRadiationPressureDisturbance( - initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCenterOfGravity_b_m())); + initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParameters().GetCenterOfGravity_b_m())); disturbances_list_.push_back(srp_dist); ThirdBodyGravity* third_body_gravity = @@ -82,10 +82,10 @@ void Disturbances::InitializeInstances(const SimulationConfig* simulation_config if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) AirDrag* air_dist = - new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParams().GetCenterOfGravity_b_m())); + new AirDrag(InitAirDrag(initialize_file_name_, structure->GetSurfaces(), structure->GetKinematicsParameters().GetCenterOfGravity_b_m())); disturbances_list_.push_back(air_dist); - MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetRMMParams())); + MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetResidualMagneticMoment())); disturbances_list_.push_back(mag_dist); GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 4aeee9634..98c3fd06b 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -29,7 +29,7 @@ void Dynamics::Initialize(SimulationConfig* simulation_configuration, const Simu simulation_time->GetOrbitRkStepTime_s(), simulation_time->GetCurrentTime_jd(), local_celestial_information->GetGlobalInformation().GetCenterBodyGravityConstant_m3_s2(), "ORBIT", relative_information); attitude_ = InitAttitude(simulation_configuration->spacecraft_file_list_[spacecraft_id], orbit_, local_celestial_information, - simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParams().GetInertiaTensor_b_kgm2(), spacecraft_id); + simulation_time->GetAttitudeRkStepTime_s(), structure->GetKinematicsParameters().GetInertiaTensor_b_kgm2(), spacecraft_id); temperature_ = InitTemperature(simulation_configuration->spacecraft_file_list_[spacecraft_id], simulation_time->GetThermalRkStepTime_s()); // To get initial value diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 784604ac1..4dc9b7c84 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -70,7 +70,7 @@ class Dynamics { * @param [in] force_b_N: Force in the body fixed frame [N] */ inline void AddForce_b_N(libra::Vector<3> force_b_N) { - orbit_->AddForce_b_N(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParams().GetMass_kg()); + orbit_->AddForce_b_N(force_b_N, attitude_->GetQuaternion_i2b(), structure_->GetKinematicsParameters().GetMass_kg()); } /** * @fn AddAcceleration_i_m_s2 diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index ca5256e75..2e307f1df 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -8,14 +8,16 @@ #include #include -Structure::Structure(SimulationConfig* simulation_configuration, const int spacecraft_id) { Initialize(simulation_configuration, spacecraft_id); } +Structure::Structure(const SimulationConfig* simulation_configuration, const int spacecraft_id) { + Initialize(simulation_configuration, spacecraft_id); +} Structure::~Structure() { delete kinematics_parameters_; delete residual_magnetic_moment_; } -void Structure::Initialize(SimulationConfig* simulation_configuration, const int spacecraft_id) { +void Structure::Initialize(const SimulationConfig* simulation_configuration, const int spacecraft_id) { // Read file name IniAccess conf = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index 2047a9c06..c83f42f91 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -24,7 +24,7 @@ class Structure { * @fn Structure * @brief Constructor */ - Structure(SimulationConfig* simulation_configuration, const int spacecraft_id); + Structure(const SimulationConfig* simulation_configuration, const int spacecraft_id); /** * @fn ~Structure * @brief Destructor @@ -34,7 +34,7 @@ class Structure { * @fn Initialize * @brief Initialize function */ - void Initialize(SimulationConfig* simulation_configuration, const int spacecraft_id); + void Initialize(const SimulationConfig* simulation_configuration, const int spacecraft_id); // Getter /** @@ -43,15 +43,15 @@ class Structure { */ inline const vector& GetSurfaces() const { return surfaces_; } /** - * @fn GetKinematicsParams + * @fn GetKinematicsParameters * @brief Return kinematics information */ - inline const KinematicsParameters& GetKinematicsParams() const { return *kinematics_parameters_; } + inline const KinematicsParameters& GetKinematicsParameters() const { return *kinematics_parameters_; } /** - * @fn GetRMMParams + * @fn GetResidualMagneticMoment * @brief Return Residual Magnetic Moment information */ - inline const ResidualMagneticMoment& GetRMMParams() const { return *residual_magnetic_moment_; } + inline const ResidualMagneticMoment& GetResidualMagneticMoment() const { return *residual_magnetic_moment_; } /** * @fn GetToSetSurfaces @@ -59,15 +59,15 @@ class Structure { */ inline vector& GetToSetSurfaces() { return surfaces_; } /** - * @fn GetToSetKinematicsParams + * @fn GetToSetKinematicsParameters * @brief Return kinematics information */ - inline KinematicsParameters& GetToSetKinematicsParams() { return *kinematics_parameters_; } + inline KinematicsParameters& GetToSetKinematicsParameters() { return *kinematics_parameters_; } /** - * @fn GetToSetRMMParams + * @fn GetToSetResidualMagneticMoment * @brief Return Residual Magnetic Moment information */ - inline ResidualMagneticMoment& GetToSetRMMParams() { return *residual_magnetic_moment_; } + inline ResidualMagneticMoment& GetToSetResidualMagneticMoment() { return *residual_magnetic_moment_; } private: KinematicsParameters* kinematics_parameters_; //!< Kinematics parameters From 937bece6b22c5bad3c7f1989d3a701a5e26edcfd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:13:26 +0100 Subject: [PATCH 0900/1086] Remove using --- src/disturbances/air_drag.cpp | 2 +- src/disturbances/air_drag.hpp | 6 +++--- src/disturbances/disturbances.hpp | 4 ++-- src/disturbances/geopotential.cpp | 8 ++++---- src/disturbances/geopotential.hpp | 10 +++++----- .../solar_radiation_pressure_disturbance.cpp | 4 ++-- src/disturbances/surface_force.cpp | 2 +- src/disturbances/surface_force.hpp | 12 ++++++------ .../multiple_spacecraft/relative_information.cpp | 12 ++++++------ .../spacecraft/structure/initialize_structure.cpp | 4 ++-- .../spacecraft/structure/initialize_structure.hpp | 2 +- src/simulation/spacecraft/structure/structure.hpp | 7 +++---- 12 files changed, 36 insertions(+), 37 deletions(-) diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 107d901c3..0a06d062d 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -11,7 +11,7 @@ #include "../library/logger/log_utility.hpp" -AirDrag::AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, +AirDrag::AirDrag(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, const double molecular_temperature_K, const double molecular_weight_g_mol, const bool is_calculation_enabled) : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled), wall_temperature_K_(wall_temperature_K), diff --git a/src/disturbances/air_drag.hpp b/src/disturbances/air_drag.hpp index c453a62f3..49de27810 100644 --- a/src/disturbances/air_drag.hpp +++ b/src/disturbances/air_drag.hpp @@ -30,7 +30,7 @@ class AirDrag : public SurfaceForce { * @param [in] molecular_weight_g_mol: Molecular weight [g/mol] * @param [in] is_calculation_enabled: Calculation flag */ - AirDrag(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, + AirDrag(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const double wall_temperature_K, const double molecular_temperature_K, const double molecular_weight_g_mol, const bool is_calculation_enabled = true); /** @@ -54,8 +54,8 @@ class AirDrag : public SurfaceForce { virtual std::string GetLogValue() const; private: - vector cn_; //!< Coefficients for out-plane force - vector ct_; //!< Coefficients for in-plane force + std::vector cn_; //!< Coefficients for out-plane force + std::vector ct_; //!< Coefficients for in-plane force double wall_temperature_K_; //!< Temperature of surface [K] double molecular_temperature_K_; //!< Temperature of atmosphere [K] double molecular_weight_g_mol_; //!< Molecular weight [g/mol] diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index d9c85bb61..e7fb21226 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -77,8 +77,8 @@ class Disturbances { Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] - vector acceleration_disturbances_list_; //!< List of acceleration disturbances - Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] + std::vector acceleration_disturbances_list_; //!< List of acceleration disturbances + Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] /** * @fn InitializeInstances diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 29a8af9b4..99ac8c41c 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -30,8 +30,8 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const degree_ = 0; } // coefficients - c_.assign(degree_ + 1, vector(degree_ + 1, 0.0)); - s_.assign(degree_ + 1, vector(degree_ + 1, 0.0)); + c_.assign(degree_ + 1, std::vector(degree_ + 1, 0.0)); + s_.assign(degree_ + 1, std::vector(degree_ + 1, 0.0)); // For actual EGM model, c_[0][0] should be 1.0 // In S2E, 0 degree term is inside the SimpleCircularOrbit calculation c_[0][0] = 0.0; @@ -91,8 +91,8 @@ void GeoPotential::CalcAccelerationEcef(const libra::Vector<3> &position_ecef_m) // Calc V and W int degree_vw = degree_ + 1; - vector> v(degree_vw + 1, vector(degree_vw + 1, 0.0)); - vector> w(degree_vw + 1, vector(degree_vw + 1, 0.0)); + std::vector> v(degree_vw + 1, std::vector(degree_vw + 1, 0.0)); + std::vector> w(degree_vw + 1, std::vector(degree_vw + 1, 0.0)); // n=m=0 v[0][0] = environment::earth_equatorial_radius_m / radius_m_; w[0][0] = 0.0; diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index eac0f4774..caf22922c 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -50,11 +50,11 @@ class GeoPotential : public AccelerationDisturbance { virtual std::string GetLogValue() const; private: - int degree_; //!< Maximum degree setting to calculate the geo-potential - int n_ = 0, m_ = 0; //!< Degree and order (FIXME: follow naming rule) - vector> c_; //!< Cosine coefficients - vector> s_; //!< Sine coefficients - Vector<3> acceleration_ecef_m_s2_; //!< Calculated acceleration in the ECEF frame [m/s2] + int degree_; //!< Maximum degree setting to calculate the geo-potential + int n_ = 0, m_ = 0; //!< Degree and order (FIXME: follow naming rule) + std::vector> c_; //!< Cosine coefficients + std::vector> s_; //!< Sine coefficients + Vector<3> acceleration_ecef_m_s2_; //!< Calculated acceleration in the ECEF frame [m/s2] // calculation double radius_m_ = 0.0; //!< Radius [m] diff --git a/src/disturbances/solar_radiation_pressure_disturbance.cpp b/src/disturbances/solar_radiation_pressure_disturbance.cpp index c34da9989..7f8dd7613 100644 --- a/src/disturbances/solar_radiation_pressure_disturbance.cpp +++ b/src/disturbances/solar_radiation_pressure_disturbance.cpp @@ -9,8 +9,8 @@ #include "../library/logger/log_utility.hpp" -SolarRadiationPressureDisturbance::SolarRadiationPressureDisturbance(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, - const bool is_calculation_enabled) +SolarRadiationPressureDisturbance::SolarRadiationPressureDisturbance(const std::vector& surfaces, + const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) : SurfaceForce(surfaces, center_of_gravity_b_m, is_calculation_enabled) {} void SolarRadiationPressureDisturbance::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index 1b8858d58..c074d2358 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -7,7 +7,7 @@ #include "../library/math/vector.hpp" -SurfaceForce::SurfaceForce(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) +SurfaceForce::SurfaceForce(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { // Initialize vectors int num = surfaces_.size(); diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index ff4232200..0c97e282a 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -28,7 +28,7 @@ class SurfaceForce : public SimpleDisturbance { * @param [in] center_of_gravity_b_m: Center of gravity position at the body frame [m] * @param [in] is_calculation_enabled: Calculation flag */ - SurfaceForce(const vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); + SurfaceForce(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled = true); /** * @fn ~SurfaceForce * @brief Destructor @@ -37,14 +37,14 @@ class SurfaceForce : public SimpleDisturbance { protected: // Spacecraft Structure parameters - const vector& surfaces_; //!< List of surfaces + const std::vector& surfaces_; //!< List of surfaces const libra::Vector<3>& center_of_gravity_b_m_; //!< Position vector of the center of mass_kg at body frame [m] // Internal calculated variables - vector normal_coefficients_; //!< coefficients for out-plane force for each surface - vector tangential_coefficients_; //!< coefficients for in-plane force for each surface - vector cos_theta_; //!< cos(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) - vector sin_theta_; //!< sin(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) + std::vector normal_coefficients_; //!< coefficients for out-plane force for each surface + std::vector tangential_coefficients_; //!< coefficients for in-plane force for each surface + std::vector cos_theta_; //!< cos(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) + std::vector sin_theta_; //!< sin(theta) for each surface (theta is the angle b/w normal vector and the direction of disturbance source) // Functions /** diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 0b09b3a9a..bb8bb799d 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -148,10 +148,10 @@ libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int tar void RelativeInformation::ResizeLists() { size_t size = dynamics_database_.size(); - rel_pos_list_i_m_.assign(size, vector>(size, libra::Vector<3>(0))); - rel_vel_list_i_m_s_.assign(size, vector>(size, libra::Vector<3>(0))); - rel_distance_list_m_.assign(size, vector(size, 0.0)); - rel_pos_list_rtn_m_.assign(size, vector>(size, libra::Vector<3>(0))); - rel_vel_list_rtn_m_s_.assign(size, vector>(size, libra::Vector<3>(0))); - rel_att_quaternion_list_.assign(size, vector(size, libra::Quaternion(0, 0, 0, 1))); + rel_pos_list_i_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); + rel_vel_list_i_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); + rel_distance_list_m_.assign(size, std::vector(size, 0.0)); + rel_pos_list_rtn_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); + rel_vel_list_rtn_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); + rel_att_quaternion_list_.assign(size, std::vector(size, libra::Quaternion(0, 0, 0, 1))); } diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index e6265a95a..1f2bdf08c 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -29,14 +29,14 @@ KinematicsParameters InitKinematicsParams(std::string ini_path) { return kinematics_params; } -vector InitSurfaces(std::string ini_path) { +std::vector InitSurfaces(std::string ini_path) { using std::cout; auto conf = IniAccess(ini_path); const char* section = "SURFACES"; const int num_surface = conf.ReadInt(section, "number_of_surfaces"); - vector surfaces; + std::vector surfaces; for (int i = 0; i < num_surface; i++) { std::string idx = std::to_string(i); diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index 6b49d23e6..c3caf607e 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -19,7 +19,7 @@ KinematicsParameters InitKinematicsParams(std::string ini_path); * @fn InitSurfaces * @brief Initialize the multiple surfaces with an ini file */ -vector InitSurfaces(std::string ini_path); +std::vector InitSurfaces(std::string ini_path); /** * @fn InitRMMParams * @brief Initialize the RMM(Residual Magnetic Moment) parameters with an ini file diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index c83f42f91..be2bfdb20 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -12,7 +12,6 @@ #include "kinematics_parameters.hpp" #include "residual_magnetic_moment.hpp" #include "surface.hpp" -using std::vector; /** * @class Structure @@ -41,7 +40,7 @@ class Structure { * @fn GetSurfaces * @brief Return surface information */ - inline const vector& GetSurfaces() const { return surfaces_; } + inline const std::vector& GetSurfaces() const { return surfaces_; } /** * @fn GetKinematicsParameters * @brief Return kinematics information @@ -57,7 +56,7 @@ class Structure { * @fn GetToSetSurfaces * @brief Return surface information */ - inline vector& GetToSetSurfaces() { return surfaces_; } + inline std::vector& GetToSetSurfaces() { return surfaces_; } /** * @fn GetToSetKinematicsParameters * @brief Return kinematics information @@ -71,7 +70,7 @@ class Structure { private: KinematicsParameters* kinematics_parameters_; //!< Kinematics parameters - vector surfaces_; //!< Surface information + std::vector surfaces_; //!< Surface information ResidualMagneticMoment* residual_magnetic_moment_; //!< Residual Magnetic Moment }; From c08147adfa0289da5b279a16af0d57613d73d2d1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:15:17 +0100 Subject: [PATCH 0901/1086] Fix initialize function name --- .../thermal/initialize_temperature.cpp | 4 +- .../thermal/initialize_temperature.hpp | 2 +- .../sample_spacecraft/sample_components.cpp | 68 +++++++++---------- .../structure/initialize_structure.cpp | 12 ++-- .../structure/initialize_structure.hpp | 10 +-- .../spacecraft/structure/structure.cpp | 4 +- 6 files changed, 50 insertions(+), 50 deletions(-) diff --git a/src/dynamics/thermal/initialize_temperature.cpp b/src/dynamics/thermal/initialize_temperature.cpp index 4cac21c36..5e40d2063 100644 --- a/src/dynamics/thermal/initialize_temperature.cpp +++ b/src/dynamics/thermal/initialize_temperature.cpp @@ -48,8 +48,8 @@ First row is for Header, data begins from the second row using std::string; using std::vector; -Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec) { - auto mainIni = IniAccess(ini_path); +Temperature* InitTemperature(const std::string file_name, const double rk_prop_step_sec) { + auto mainIni = IniAccess(file_name); vector vnodes; vector> cij; diff --git a/src/dynamics/thermal/initialize_temperature.hpp b/src/dynamics/thermal/initialize_temperature.hpp index a8f8792b6..e4d6ba888 100644 --- a/src/dynamics/thermal/initialize_temperature.hpp +++ b/src/dynamics/thermal/initialize_temperature.hpp @@ -9,6 +9,6 @@ #include "temperature.hpp" class Temperature; -Temperature* InitTemperature(const std::string ini_path, const double rk_prop_step_sec); +Temperature* InitTemperature(const std::string file_name, const double rk_prop_step_sec); #endif // S2E_DYNAMICS_THERMAL_INITIALIZE_TEMPERATURE_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index d8049845c..0d0ed1235 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -26,68 +26,68 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur hils_port_manager_ = new HilsPortManager(); // GyroSensor - std::string ini_path = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); + std::string file_name = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); gyro_ = new GyroSensor( - InitGyroSensor(clock_gen, pcu_->GetPowerPort(1), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); + InitGyroSensor(clock_gen, pcu_->GetPowerPort(1), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // Magnetometer - ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); + file_name = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); mag_sensor_ = - new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_environment_->GetGeomagneticField()))); // StarSensor - ini_path = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - stt_ = new StarSensor(InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + file_name = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + stt_ = new StarSensor(InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_environment_)); // SunSensor - ini_path = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, &(local_environment_->GetSolarRadiationPressure()), + file_name = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, file_name, &(local_environment_->GetSolarRadiationPressure()), &(local_environment_->GetCelestialInformation()))); // GNSS-R - ini_path = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - gnss_ = new GnssReceiver( - InitGnssReceiver(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_, &(glo_env_->GetGnssSatellites()), &(glo_env_->GetSimulationTime()))); + file_name = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + gnss_ = new GnssReceiver(InitGnssReceiver(clock_gen, pcu_->GetPowerPort(2), 1, file_name, dynamics_, &(glo_env_->GetGnssSatellites()), + &(glo_env_->GetSimulationTime()))); // Magnetorquer - ini_path = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); + file_name = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); mag_torquer_ = - new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, glo_env_->GetSimulationTime().GetComponentStepTime_s(), + new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), &(local_environment_->GetGeomagneticField()))); // RW - ini_path = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - rw_ = new ReactionWheel(InitReactionWheel(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, dynamics_->GetAttitude().GetPropStep(), + file_name = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + rw_ = new ReactionWheel(InitReactionWheel(clock_gen, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep(), glo_env_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator - ini_path = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_gen, ini_path, dynamics_)); + file_name = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_gen, file_name, dynamics_)); // Thruster - ini_path = iniAccess.ReadString("COMPONENT_FILES", "thruster_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - thruster_ = new SimpleThruster(InitSimpleThruster(clock_gen, pcu_->GetPowerPort(2), 1, ini_path, structure_, dynamics)); + file_name = iniAccess.ReadString("COMPONENT_FILES", "thruster_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + thruster_ = new SimpleThruster(InitSimpleThruster(clock_gen, pcu_->GetPowerPort(2), 1, file_name, structure_, dynamics)); // Force Generator - ini_path = iniAccess.ReadString("COMPONENT_FILES", "force_generator_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_gen, ini_path, dynamics_)); + file_name = iniAccess.ReadString("COMPONENT_FILES", "force_generator_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_gen, file_name, dynamics_)); // Antenna - ini_path = iniAccess.ReadString("COMPONENT_FILES", "antenna_file"); - config_->main_logger_->CopyFileToLogDirectory(ini_path); - antenna_ = new Antenna(InitAntenna(1, ini_path)); + file_name = iniAccess.ReadString("COMPONENT_FILES", "antenna_file"); + config_->main_logger_->CopyFileToLogDirectory(file_name); + antenna_ = new Antenna(InitAntenna(1, file_name)); // PCU power port initial control pcu_->GetPowerPort(0)->SetVoltage_V(3.3); diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 1f2bdf08c..18a791279 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -9,8 +9,8 @@ #include #define MIN_VAL 1e-6 -KinematicsParameters InitKinematicsParams(std::string ini_path) { - auto conf = IniAccess(ini_path); +KinematicsParameters InitKinematicsParameters(std::string file_name) { + auto conf = IniAccess(file_name); const char* section = "KINEMATIC_PARAMETERS"; libra::Vector<3> center_of_gravity_b_m; @@ -29,10 +29,10 @@ KinematicsParameters InitKinematicsParams(std::string ini_path) { return kinematics_params; } -std::vector InitSurfaces(std::string ini_path) { +std::vector InitSurfaces(std::string file_name) { using std::cout; - auto conf = IniAccess(ini_path); + auto conf = IniAccess(file_name); const char* section = "SURFACES"; const int num_surface = conf.ReadInt(section, "number_of_surfaces"); @@ -106,8 +106,8 @@ std::vector InitSurfaces(std::string ini_path) { return surfaces; } -ResidualMagneticMoment InitRMMParams(std::string ini_path) { - auto conf = IniAccess(ini_path); +ResidualMagneticMoment InitResidualMagneticMoment(std::string file_name) { + auto conf = IniAccess(file_name); const char* section = "RESIDUAL_MAGNETIC_MOMENT"; libra::Vector<3> rmm_const_b; diff --git a/src/simulation/spacecraft/structure/initialize_structure.hpp b/src/simulation/spacecraft/structure/initialize_structure.hpp index c3caf607e..59311219a 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.hpp +++ b/src/simulation/spacecraft/structure/initialize_structure.hpp @@ -11,19 +11,19 @@ #include /** - * @fn InitKinematicsParams + * @fn InitKinematicsParameters * @brief Initialize the kinematics parameters with an ini file */ -KinematicsParameters InitKinematicsParams(std::string ini_path); +KinematicsParameters InitKinematicsParameters(std::string file_name); /** * @fn InitSurfaces * @brief Initialize the multiple surfaces with an ini file */ -std::vector InitSurfaces(std::string ini_path); +std::vector InitSurfaces(std::string file_name); /** - * @fn InitRMMParams + * @fn InitResidualMagneticMoment * @brief Initialize the RMM(Residual Magnetic Moment) parameters with an ini file */ -ResidualMagneticMoment InitRMMParams(std::string ini_path); +ResidualMagneticMoment InitResidualMagneticMoment(std::string file_name); #endif // S2E_SIMULATION_SPACECRAFT_STRUCTURE_INITIALIZE_STRUCTURE_HPP_ diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 2e307f1df..92e8bc0ba 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -24,7 +24,7 @@ void Structure::Initialize(const SimulationConfig* simulation_configuration, con // Save ini file simulation_configuration->main_logger_->CopyFileToLogDirectory(ini_fname); // Initialize - kinematics_parameters_ = new KinematicsParameters(InitKinematicsParams(ini_fname)); + kinematics_parameters_ = new KinematicsParameters(InitKinematicsParameters(ini_fname)); surfaces_ = InitSurfaces(ini_fname); - residual_magnetic_moment_ = new ResidualMagneticMoment(InitRMMParams(ini_fname)); + residual_magnetic_moment_ = new ResidualMagneticMoment(InitResidualMagneticMoment(ini_fname)); } From 64912a7467900501b4fa1e985738766caaa0e9c5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:20:53 +0100 Subject: [PATCH 0902/1086] Fix sample components --- src/dynamics/dynamics.hpp | 4 +- src/simulation/case/sample_case.cpp | 24 ++-- src/simulation/case/simulation_case.cpp | 6 +- src/simulation/case/simulation_case.hpp | 6 +- .../ground_station/ground_station.cpp | 12 +- .../ground_station/ground_station.hpp | 4 +- .../sample_ground_station.cpp | 4 +- .../sample_ground_station.hpp | 4 +- .../sample_ground_station_components.cpp | 8 +- .../sample_ground_station_components.hpp | 4 +- .../sample_spacecraft/sample_components.cpp | 118 +++++++++--------- .../sample_spacecraft/sample_components.hpp | 25 ++-- 12 files changed, 112 insertions(+), 107 deletions(-) diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 4dc9b7c84..244785b7c 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -28,7 +28,7 @@ class Dynamics { /** * @fn Dynamics * @brief Constructor - * @param [in] simulation_configuration: Simulation config + * @param [in] simulation_configuration: Simulation configuration * @param [in] simulation_time: Simulation time * @param [in] local_celestial_information: Local celestial information * @param [in] spacecraft_id: Spacecraft ID of the spacecraft @@ -115,7 +115,7 @@ class Dynamics { /** * @fn Initialize * @brief Initialize function - * @param [in] simulation_configuration: Simulation config + * @param [in] simulation_configuration: Simulation configuration * @param [in] simulation_time: Simulation time * @param [in] local_celestial_information: Local celestial information * @param [in] spacecraft_id: Spacecraft ID of the spacecraft diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 8f04f9db0..152020b85 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -18,12 +18,12 @@ void SampleCase::Initialize() { // Instantiate the target of the simulation // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini const int spacecraft_id = 0; - sample_sat_ = new SampleSat(&sim_config_, glo_env_, spacecraft_id); + sample_sat_ = new SampleSat(&sim_config_, global_environment_, spacecraft_id); const int gs_id = 0; sample_gs_ = new SampleGS(&sim_config_, gs_id); // Register the log output - glo_env_->LogSetup(*(sim_config_.main_logger_)); + global_environment_->LogSetup(*(sim_config_.main_logger_)); sample_sat_->LogSetup(*(sim_config_.main_logger_)); sample_gs_->LogSetup(*(sim_config_.main_logger_)); @@ -32,27 +32,27 @@ void SampleCase::Initialize() { // Start the simulation cout << "\nSimulationDateTime \n"; - glo_env_->GetSimulationTime().PrintStartDateTime(); + global_environment_->GetSimulationTime().PrintStartDateTime(); } void SampleCase::Main() { - glo_env_->Reset(); // for MonteCarlo Sim - while (!glo_env_->GetSimulationTime().GetState().finish) { + global_environment_->Reset(); // for MonteCarlo Sim + while (!global_environment_->GetSimulationTime().GetState().finish) { // Logging - if (glo_env_->GetSimulationTime().GetState().log_output) { + if (global_environment_->GetSimulationTime().GetState().log_output) { sim_config_.main_logger_->WriteValues(); } // Global Environment Update - glo_env_->Update(); + global_environment_->Update(); // Spacecraft Update - sample_sat_->Update(&(glo_env_->GetSimulationTime())); + sample_sat_->Update(&(global_environment_->GetSimulationTime())); // Ground Station Update - sample_gs_->Update(glo_env_->GetCelestialInformation().GetEarthRotation(), *sample_sat_); + sample_gs_->Update(global_environment_->GetCelestialInformation().GetEarthRotation(), *sample_sat_); // Debug output - if (glo_env_->GetSimulationTime().GetState().disp_output) { - cout << "Progresss: " << glo_env_->GetSimulationTime().GetProgressionRate() << "%\r"; + if (global_environment_->GetSimulationTime().GetState().disp_output) { + cout << "Progresss: " << global_environment_->GetSimulationTime().GetProgressionRate() << "%\r"; } } } @@ -78,7 +78,7 @@ string SampleCase::GetLogValue() const { // auto omega_b = sample_sat->dynamics_->GetAttitude().GetOmega_b(); // Need to match the contents of log with header setting above - str_tmp += WriteScalar(glo_env_->GetSimulationTime().GetElapsedTime_s()); + str_tmp += WriteScalar(global_environment_->GetSimulationTime().GetElapsedTime_s()); // str_tmp += WriteVector(pos_i, 16); // str_tmp += WriteVector(vel_i, 10); // str_tmp += WriteQuaternion(quat_i2b); diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index d6a9b487a..2df8cd305 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -22,7 +22,7 @@ SimulationCase::SimulationCase(std::string ini_base) { sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); - glo_env_ = new GlobalEnvironment(&sim_config_); + global_environment_ = new GlobalEnvironment(&sim_config_); } SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); @@ -41,6 +41,6 @@ SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); // Global Environment - glo_env_ = new GlobalEnvironment(&sim_config_); + global_environment_ = new GlobalEnvironment(&sim_config_); } -SimulationCase::~SimulationCase() { delete glo_env_; } +SimulationCase::~SimulationCase() { delete global_environment_; } diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 4d1a2fb30..0ef3738d3 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -68,11 +68,11 @@ class SimulationCase : public ILoggable { * @fn GetGlobalEnvironment * @brief Return global environment */ - inline const GlobalEnvironment& GetGlobalEnvironment() const { return *glo_env_; } + inline const GlobalEnvironment& GetGlobalEnvironment() const { return *global_environment_; } protected: - SimulationConfig sim_config_; //!< Simulation setting - GlobalEnvironment* glo_env_; //!< Global Environment + SimulationConfig sim_config_; //!< Simulation setting + GlobalEnvironment* global_environment_; //!< Global Environment }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 64fe11e06..4dcb6393c 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -13,9 +13,9 @@ #include #include -GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id) { - Initialize(gs_id_, config); - num_sc_ = config->number_of_simulated_spacecraft_; +GroundStation::GroundStation(SimulationConfig* configuration, int gs_id) : gs_id_(gs_id) { + Initialize(gs_id_, configuration); + num_sc_ = configuration->number_of_simulated_spacecraft_; for (int i = 0; i < num_sc_; i++) { is_visible_[i] = false; } @@ -23,8 +23,8 @@ GroundStation::GroundStation(SimulationConfig* config, int gs_id) : gs_id_(gs_id GroundStation::~GroundStation() {} -void GroundStation::Initialize(int gs_id, SimulationConfig* config) { - std::string gs_ini_path = config->ground_station_file_list_[0]; +void GroundStation::Initialize(int gs_id, SimulationConfig* configuration) { + std::string gs_ini_path = configuration->ground_station_file_list_[0]; auto conf = IniAccess(gs_ini_path); const char* section_base = "GROUND_STATION_"; @@ -39,7 +39,7 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* config) { elevation_limit_angle_deg_ = conf.ReadDouble(Section, "elevation_limit_angle_deg"); - config->main_logger_->CopyFileToLogDirectory(gs_ini_path); + configuration->main_logger_->CopyFileToLogDirectory(gs_ini_path); } void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 8d5fca4f5..59fac8be7 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -23,7 +23,7 @@ class GroundStation : public ILoggable { * @fn GroundStation * @brief Constructor */ - GroundStation(SimulationConfig* config, int gs_id_); + GroundStation(SimulationConfig* configuration, int gs_id_); /** * @fn ~GroundStation * @brief Destructor @@ -34,7 +34,7 @@ class GroundStation : public ILoggable { * @fn Initialize * @brief Virtual function to initialize the ground station */ - virtual void Initialize(int gs_id, SimulationConfig* config); + virtual void Initialize(int gs_id, SimulationConfig* configuration); /** * @fn LogSetup * @brief Virtual function to log output setting for ground station related components diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index d76257c6c..ba852912d 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -7,11 +7,11 @@ #include "sample_ground_station_components.hpp" -SampleGS::SampleGS(SimulationConfig* config, int gs_id) : GroundStation(config, gs_id) { Initialize(config); } +SampleGS::SampleGS(SimulationConfig* configuration, int gs_id) : GroundStation(configuration, gs_id) { Initialize(configuration); } SampleGS::~SampleGS() { delete components_; } -void SampleGS::Initialize(SimulationConfig* config) { components_ = new SampleGSComponents(config); } +void SampleGS::Initialize(SimulationConfig* configuration) { components_ = new SampleGSComponents(configuration); } void SampleGS::LogSetup(Logger& logger) { GroundStation::LogSetup(logger); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 41a04a193..d84c40d6d 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -26,7 +26,7 @@ class SampleGS : public GroundStation { * @fn SampleGS * @brief Constructor */ - SampleGS(SimulationConfig* config, int gs_id); + SampleGS(SimulationConfig* configuration, int gs_id); /** * @fn ~SampleGS * @brief Destructor @@ -37,7 +37,7 @@ class SampleGS : public GroundStation { * @fn Initialize * @brief Override function of Initialize in GroundStation class */ - virtual void Initialize(SimulationConfig* config); + virtual void Initialize(SimulationConfig* configuration); /** * @fn LogSetup * @brief Override function of LogSetup in GroundStation class diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 95c5ed8a1..287d500a6 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -6,14 +6,14 @@ #include -SampleGSComponents::SampleGSComponents(const SimulationConfig* config) : config_(config) { - IniAccess iniAccess = IniAccess(config_->ground_station_file_list_[0]); +SampleGSComponents::SampleGSComponents(const SimulationConfig* configuration) : configuration_(configuration) { + IniAccess iniAccess = IniAccess(configuration_->ground_station_file_list_[0]); std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); - config_->main_logger_->CopyFileToLogDirectory(ant_ini_path); + configuration_->main_logger_->CopyFileToLogDirectory(ant_ini_path); antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); - config_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); + configuration_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); gs_calculator_ = new GroundStationCalculator(InitGsCalculator(gscalculator_ini_path)); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 7d4f235dc..8954e41dd 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -19,7 +19,7 @@ class SampleGSComponents { * @fn SampleGSComponents * @brief Constructor */ - SampleGSComponents(const SimulationConfig* config); + SampleGSComponents(const SimulationConfig* configuration); /** * @fn ~SampleGSComponents * @brief Destructor @@ -46,7 +46,7 @@ class SampleGSComponents { private: Antenna* antenna_; //!< Antenna on ground station GroundStationCalculator* gs_calculator_; //!< Ground station calculation algorithm - const SimulationConfig* config_; //!< Simulation setting + const SimulationConfig* configuration_; //!< Simulation setting }; #endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 0d0ed1235..a9ff00f92 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -10,83 +10,87 @@ #include "sample_port_configuration.hpp" SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, - const GlobalEnvironment* global_environment, const SimulationConfig* config, ClockGenerator* clock_gen, - const int spacecraft_id) - : config_(config), dynamics_(dynamics), structure_(structure), local_environment_(local_environment), glo_env_(global_environment) { - IniAccess iniAccess = IniAccess(config_->spacecraft_file_list_[spacecraft_id]); + const GlobalEnvironment* global_environment, const SimulationConfig* configuration, + ClockGenerator* clock_generator, const int spacecraft_id) + : configuration_(configuration), + dynamics_(dynamics), + structure_(structure), + local_environment_(local_environment), + global_environment_(global_environment) { + IniAccess iniAccess = IniAccess(configuration_->spacecraft_file_list_[spacecraft_id]); // PCU power port connection - pcu_ = new PowerControlUnit(clock_gen); + pcu_ = new PowerControlUnit(clock_generator); pcu_->ConnectPort(0, 0.5, 3.3, 1.0); // OBC: assumed power consumption is defined here pcu_->ConnectPort(1, 1.0); // GyroSensor: assumed power consumption is defined inside the InitGyroSensor pcu_->ConnectPort(2, 1.0); // for other all components // Components - obc_ = new OnBoardComputer(1, clock_gen, pcu_->GetPowerPort(0)); + obc_ = new OnBoardComputer(1, clock_generator, pcu_->GetPowerPort(0)); hils_port_manager_ = new HilsPortManager(); // GyroSensor std::string file_name = iniAccess.ReadString("COMPONENT_FILES", "gyro_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - gyro_ = new GyroSensor( - InitGyroSensor(clock_gen, pcu_->GetPowerPort(1), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + gyro_sensor_ = new GyroSensor(InitGyroSensor(clock_generator, pcu_->GetPowerPort(1), 1, file_name, + global_environment_->GetSimulationTime().GetComponentStepTime_s(), dynamics_)); // Magnetometer file_name = iniAccess.ReadString("COMPONENT_FILES", "magetometer_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - mag_sensor_ = - new Magnetometer(InitMagetometer(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - &(local_environment_->GetGeomagneticField()))); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + magnetometer_ = new Magnetometer(InitMagetometer(clock_generator, pcu_->GetPowerPort(2), 1, file_name, + global_environment_->GetSimulationTime().GetComponentStepTime_s(), + &(local_environment_->GetGeomagneticField()))); // StarSensor file_name = iniAccess.ReadString("COMPONENT_FILES", "stt_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - stt_ = new StarSensor(InitStarSensor(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - dynamics_, local_environment_)); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + star_sensor_ = new StarSensor(InitStarSensor(clock_generator, pcu_->GetPowerPort(2), 1, file_name, + global_environment_->GetSimulationTime().GetComponentStepTime_s(), dynamics_, local_environment_)); // SunSensor file_name = iniAccess.ReadString("COMPONENT_FILES", "ss_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - sun_sensor_ = new SunSensor(InitSunSensor(clock_gen, pcu_->GetPowerPort(2), 1, file_name, &(local_environment_->GetSolarRadiationPressure()), + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + sun_sensor_ = new SunSensor(InitSunSensor(clock_generator, pcu_->GetPowerPort(2), 1, file_name, &(local_environment_->GetSolarRadiationPressure()), &(local_environment_->GetCelestialInformation()))); // GNSS-R file_name = iniAccess.ReadString("COMPONENT_FILES", "gnss_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - gnss_ = new GnssReceiver(InitGnssReceiver(clock_gen, pcu_->GetPowerPort(2), 1, file_name, dynamics_, &(glo_env_->GetGnssSatellites()), - &(glo_env_->GetSimulationTime()))); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + gnss_receiver_ = new GnssReceiver(InitGnssReceiver(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_, + &(global_environment_->GetGnssSatellites()), &(global_environment_->GetSimulationTime()))); // Magnetorquer file_name = iniAccess.ReadString("COMPONENT_FILES", "magetorquer_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - mag_torquer_ = - new Magnetorquer(InitMagnetorquer(clock_gen, pcu_->GetPowerPort(2), 1, file_name, glo_env_->GetSimulationTime().GetComponentStepTime_s(), - &(local_environment_->GetGeomagneticField()))); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + magnetorquer_ = new Magnetorquer(InitMagnetorquer(clock_generator, pcu_->GetPowerPort(2), 1, file_name, + global_environment_->GetSimulationTime().GetComponentStepTime_s(), + &(local_environment_->GetGeomagneticField()))); // RW file_name = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - rw_ = new ReactionWheel(InitReactionWheel(clock_gen, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep(), - glo_env_->GetSimulationTime().GetComponentStepTime_s())); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + reaction_wheel_ = new ReactionWheel(InitReactionWheel(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep(), + global_environment_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator file_name = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_gen, file_name, dynamics_)); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + torque_generator_ = new TorqueGenerator(InitializeTorqueGenerator(clock_generator, file_name, dynamics_)); // Thruster file_name = iniAccess.ReadString("COMPONENT_FILES", "thruster_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - thruster_ = new SimpleThruster(InitSimpleThruster(clock_gen, pcu_->GetPowerPort(2), 1, file_name, structure_, dynamics)); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + thruster_ = new SimpleThruster(InitSimpleThruster(clock_generator, pcu_->GetPowerPort(2), 1, file_name, structure_, dynamics)); // Force Generator file_name = iniAccess.ReadString("COMPONENT_FILES", "force_generator_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); - force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_gen, file_name, dynamics_)); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); + force_generator_ = new ForceGenerator(InitializeForceGenerator(clock_generator, file_name, dynamics_)); // Antenna file_name = iniAccess.ReadString("COMPONENT_FILES", "antenna_file"); - config_->main_logger_->CopyFileToLogDirectory(file_name); + configuration_->main_logger_->CopyFileToLogDirectory(file_name); antenna_ = new Antenna(InitAntenna(1, file_name)); // PCU power port initial control @@ -97,23 +101,23 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur /** Examples **/ // ChangeStructure: Please uncomment change_structure related codes if you want to test the change_structure - // change_structure_ = new ExampleChangeStructure(clock_gen, structure_); + // change_structure_ = new ExampleChangeStructure(clock_generator, structure_); // UART tutorial. Comment out when not in use. - // exp_hils_uart_responder_ = new ExampleSerialCommunicationForHils(clock_gen, 1, obc_, 3, 9600, hils_port_manager_, 1); - // exp_hils_uart_sender_ = new ExampleSerialCommunicationForHils(clock_gen, 0, obc_, 4, 9600, hils_port_manager_, 0); + // exp_hils_uart_responder_ = new ExampleSerialCommunicationForHils(clock_generator, 1, obc_, 3, 9600, hils_port_manager_, 1); + // exp_hils_uart_sender_ = new ExampleSerialCommunicationForHils(clock_generator, 0, obc_, 4, 9600, hils_port_manager_, 0); // I2C tutorial. Comment out when not in use. - // exp_hils_i2c_controller_ = new ExampleI2cControllerForHils(30, clock_gen, 5, 115200, 256, 256, hils_port_manager_); - // exp_hils_i2c_target_ = new ExampleI2cTargetForHils(1, clock_gen, 0, 0x44, obc_, 6, hils_port_manager_); + // exp_hils_i2c_controller_ = new ExampleI2cControllerForHils(30, clock_generator, 5, 115200, 256, 256, hils_port_manager_); + // exp_hils_i2c_target_ = new ExampleI2cTargetForHils(1, clock_generator, 0, 0x44, obc_, 6, hils_port_manager_); /**************/ // actuator debug output // libra::Vector mag_moment_c{0.01}; - // mag_torquer_->SetOutputMagneticMoment_c_Am2(mag_moment_c); - // rw_->SetTargetTorque_rw_Nm(0.01); - // rw_->SetDriveFlag(true); + // magnetorquer_->SetOutputMagneticMoment_c_Am2(mag_moment_c); + // reaction_wheel_->SetTargetTorque_rw_Nm(0.01); + // reaction_wheel_->SetDriveFlag(true); // thruster_->SetDuty(0.9); // force generator debug output @@ -132,13 +136,13 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur } SampleComponents::~SampleComponents() { - delete gyro_; - delete mag_sensor_; - delete stt_; + delete gyro_sensor_; + delete magnetometer_; + delete star_sensor_; delete sun_sensor_; - delete gnss_; - delete mag_torquer_; - delete rw_; + delete gnss_receiver_; + delete magnetorquer_; + delete reaction_wheel_; delete thruster_; delete force_generator_; delete torque_generator_; @@ -162,21 +166,21 @@ libra::Vector<3> SampleComponents::GenerateForce_b_N() { libra::Vector<3> SampleComponents::GenerateTorque_b_Nm() { libra::Vector<3> torque_b_Nm_(0.0); - torque_b_Nm_ += mag_torquer_->GetOutputTorque_b_Nm(); - torque_b_Nm_ += rw_->GetOutputTorque_b_Nm(); + torque_b_Nm_ += magnetorquer_->GetOutputTorque_b_Nm(); + torque_b_Nm_ += reaction_wheel_->GetOutputTorque_b_Nm(); torque_b_Nm_ += thruster_->GetOutputTorque_b_Nm(); torque_b_Nm_ += torque_generator_->GetGeneratedTorque_b_Nm(); return torque_b_Nm_; } void SampleComponents::LogSetup(Logger& logger) { - logger.AddLogList(gyro_); - logger.AddLogList(mag_sensor_); - logger.AddLogList(stt_); + logger.AddLogList(gyro_sensor_); + logger.AddLogList(magnetometer_); + logger.AddLogList(star_sensor_); logger.AddLogList(sun_sensor_); - logger.AddLogList(gnss_); - logger.AddLogList(mag_torquer_); - logger.AddLogList(rw_); + logger.AddLogList(gnss_receiver_); + logger.AddLogList(magnetorquer_); + logger.AddLogList(reaction_wheel_); logger.AddLogList(thruster_); logger.AddLogList(force_generator_); logger.AddLogList(torque_generator_); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 0c808419b..724cb0c2f 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -54,7 +54,8 @@ class SampleComponents : public InstalledComponents { * @brief Constructor */ SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, - const GlobalEnvironment* global_environment, const SimulationConfig* config, ClockGenerator* clock_gen, const int spacecraft_id); + const GlobalEnvironment* global_environment, const SimulationConfig* configuration, ClockGenerator* clock_generator, + const int spacecraft_id); /** * @fn ~SampleComponents * @brief Destructor @@ -87,13 +88,13 @@ class SampleComponents : public InstalledComponents { HilsPortManager* hils_port_manager_; //!< Port manager for HILS test // AOCS - GyroSensor* gyro_; //!< GyroSensor sensor - Magnetometer* mag_sensor_; //!< Magnetmeter - StarSensor* stt_; //!< Star sensor + GyroSensor* gyro_sensor_; //!< GyroSensor sensor + Magnetometer* magnetometer_; //!< Magnetometer + StarSensor* star_sensor_; //!< Star sensor SunSensor* sun_sensor_; //!< Sun sensor - GnssReceiver* gnss_; //!< GNSS receiver - Magnetorquer* mag_torquer_; //!< Magnetorquer - ReactionWheel* rw_; //!< Reaction Wheel + GnssReceiver* gnss_receiver_; //!< GNSS receiver + Magnetorquer* magnetorquer_; //!< Magnetorquer + ReactionWheel* reaction_wheel_; //!< Reaction Wheel SimpleThruster* thruster_; //!< Thruster ForceGenerator* force_generator_; //!< Ideal Force Generator TorqueGenerator* torque_generator_; //!< Ideal Torque Generator @@ -111,11 +112,11 @@ class SampleComponents : public InstalledComponents { */ // States - const SimulationConfig* config_; //!< Simulation settings - const Dynamics* dynamics_; //!< Dynamics information of the spacecraft - Structure* structure_; //!< Structure information of the spacecraft - const LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft - const GlobalEnvironment* glo_env_; //!< Global environment information + const SimulationConfig* configuration_; //!< Simulation settings + const Dynamics* dynamics_; //!< Dynamics information of the spacecraft + Structure* structure_; //!< Structure information of the spacecraft + const LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft + const GlobalEnvironment* global_environment_; //!< Global environment information }; #endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ From 3a7790fa460659b428901ccf3cb9edf58d5dd600 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:25:57 +0100 Subject: [PATCH 0903/1086] Add const for simulation config --- data/sample/initialize_files/sample_simulation_base.ini | 3 ++- src/dynamics/dynamics.cpp | 4 ++-- src/dynamics/dynamics.hpp | 4 ++-- src/simulation/spacecraft/spacecraft.cpp | 8 ++++---- src/simulation/spacecraft/spacecraft.hpp | 8 ++++---- 5 files changed, 14 insertions(+), 13 deletions(-) diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 185a41fdd..62dc896bb 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -132,7 +132,8 @@ save_initialize_files = ENABLE // File name must not over 256 characters (defined in initialize.h as MAX_CHAR_NUM) // If you want to add a spacecraft, create the corresponding Sat.ini, and specify it as sat_file(1), sat_file(2)... . number_of_simulated_spacecraft = 1 +number_of_simulated_ground_station = 1 spacecraft_file(0) = ../../data/sample/initialize_files/sample_satellite.ini -ground_station_file = ../../data/sample/initialize_files/sample_ground_station.ini +ground_station_file(0) = ../../data/sample/initialize_files/sample_ground_station.ini gnss_file = ../../data/sample/initialize_files/sample_gnss.ini log_file_save_directory = ../../data/sample/logs/ diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 98c3fd06b..47523050a 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -7,7 +7,7 @@ #include "../simulation/multiple_spacecraft/relative_information.hpp" -Dynamics::Dynamics(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, +Dynamics::Dynamics(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information) { Initialize(simulation_configuration, simulation_time, local_celestial_information, spacecraft_id, structure, relative_information); @@ -19,7 +19,7 @@ Dynamics::~Dynamics() { delete temperature_; } -void Dynamics::Initialize(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, +void Dynamics::Initialize(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information) { structure_ = structure; diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 244785b7c..3bb221be6 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -35,7 +35,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] relative_information: Relative information */ - Dynamics(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + Dynamics(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** @@ -122,7 +122,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] relative_information: Relative information */ - void Initialize(SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + void Initialize(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information = (RelativeInformation*)nullptr); }; diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index de49a944b..c3d25b6bd 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -8,12 +8,12 @@ #include #include -Spacecraft::Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) +Spacecraft::Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) : spacecraft_id_(spacecraft_id) { Initialize(simulation_configuration, global_environment, spacecraft_id); } -Spacecraft::Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +Spacecraft::Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id) : spacecraft_id_(spacecraft_id) { Initialize(simulation_configuration, global_environment, relative_information, spacecraft_id); @@ -30,7 +30,7 @@ Spacecraft::~Spacecraft() { delete components_; } -void Spacecraft::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { +void Spacecraft::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { clock_generator_.ClearTimerCount(); structure_ = new Structure(simulation_configuration, spacecraft_id); local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); @@ -43,7 +43,7 @@ void Spacecraft::Initialize(SimulationConfig* simulation_configuration, const Gl relative_information_ = nullptr; } -void Spacecraft::Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +void Spacecraft::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id) { clock_generator_.ClearTimerCount(); structure_ = new Structure(simulation_configuration, spacecraft_id); diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index e84138eb7..2f1abdd20 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -25,12 +25,12 @@ class Spacecraft { * @fn Spacecraft * @brief Constructor for single satellite simulation */ - Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Spacecraft * @brief Constructor for multiple satellite simulation */ - Spacecraft(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, + Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id); /** @@ -48,12 +48,12 @@ class Spacecraft { * @fn Initialize * @brief Initialize function for single spacecraft simulation */ - virtual void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + virtual void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Initialize * @brief Initialize function for multiple spacecraft simulation */ - virtual void Initialize(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + virtual void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id); /** From 7b4bb5ef5cf8e85b88b3ac56e201a34c46aab3d8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:27:43 +0100 Subject: [PATCH 0904/1086] Add unsigned --- .../spacecraft/sample_spacecraft/sample_components.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_components.hpp | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.cpp | 2 +- .../spacecraft/sample_spacecraft/sample_spacecraft.hpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index a9ff00f92..7e295f256 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -11,7 +11,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* global_environment, const SimulationConfig* configuration, - ClockGenerator* clock_generator, const int spacecraft_id) + ClockGenerator* clock_generator, const unsigned int spacecraft_id) : configuration_(configuration), dynamics_(dynamics), structure_(structure), diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index 724cb0c2f..d8a29ea3c 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -55,7 +55,7 @@ class SampleComponents : public InstalledComponents { */ SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, const GlobalEnvironment* global_environment, const SimulationConfig* configuration, ClockGenerator* clock_generator, - const int spacecraft_id); + const unsigned int spacecraft_id); /** * @fn ~SampleComponents * @brief Destructor diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 1bc37c63c..cd6b7f6b7 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -10,7 +10,7 @@ #include "sample_components.hpp" -SampleSat::SampleSat(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) +SampleSat::SampleSat(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id) : Spacecraft(simulation_configuration, global_environment, spacecraft_id) { sample_components_ = new SampleComponents(dynamics_, structure_, local_environment_, global_environment, simulation_configuration, &clock_generator_, spacecraft_id); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index b89596e57..fa74d57fd 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -21,7 +21,7 @@ class SampleSat : public Spacecraft { * @fn SampleSat * @brief Constructor */ - SampleSat(SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + SampleSat(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id); /** * @fn GetInstalledComponents From 1e6ce3611e37362cc361415a2201de1dea3f5469 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:30:53 +0100 Subject: [PATCH 0905/1086] Fix private and function argument name --- .../relative_information.cpp | 116 +++++++++--------- .../relative_information.hpp | 82 ++++++------- 2 files changed, 102 insertions(+), 96 deletions(-) diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index bb8bb799d..33e4f1ea7 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -10,25 +10,29 @@ RelativeInformation::RelativeInformation() {} RelativeInformation::~RelativeInformation() {} void RelativeInformation::Update() { - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < dynamics_database_.size(); reference_sat_id++) { + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < dynamics_database_.size(); reference_spacecraft_id++) { // Position - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); - rel_pos_list_i_m_[target_sat_id][reference_sat_id] = target_sat_pos_i - reference_sat_pos_i; - rel_pos_list_rtn_m_[target_sat_id][reference_sat_id] = CalcRelativePosition_rtn_m(target_sat_id, reference_sat_id); + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetPosition_i_m(); + relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id] = target_sat_pos_i - reference_sat_pos_i; + relative_position_list_rtn_m_[target_spacecraft_id][reference_spacecraft_id] = + CalcRelativePosition_rtn_m(target_spacecraft_id, reference_spacecraft_id); // Distance - rel_distance_list_m_[target_sat_id][reference_sat_id] = CalcNorm(rel_pos_list_i_m_[target_sat_id][reference_sat_id]); + relative_distance_list_m_[target_spacecraft_id][reference_spacecraft_id] = + CalcNorm(relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id]); // Velocity - libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); - libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetVelocity_i_m_s(); - rel_vel_list_i_m_s_[target_sat_id][reference_sat_id] = target_sat_vel_i - reference_sat_vel_i; - rel_vel_list_rtn_m_s_[target_sat_id][reference_sat_id] = CalcRelativeVelocity_rtn_m_s(target_sat_id, reference_sat_id); + libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); + libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); + relative_velocity_list_i_m_s_[target_spacecraft_id][reference_spacecraft_id] = target_sat_vel_i - reference_sat_vel_i; + relative_velocity_list_rtn_m_s_[target_spacecraft_id][reference_spacecraft_id] = + CalcRelativeVelocity_rtn_m_s(target_spacecraft_id, reference_spacecraft_id); // Attitude Quaternion - rel_att_quaternion_list_[target_sat_id][reference_sat_id] = CalcRelativeAttitudeQuaternion(target_sat_id, reference_sat_id); + relative_attitude_quaternion_list_[target_spacecraft_id][reference_spacecraft_id] = + CalcRelativeAttitudeQuaternion(target_spacecraft_id, reference_spacecraft_id); } } } @@ -45,27 +49,29 @@ void RelativeInformation::RemoveDynamicsInfo(const int spacecraft_id) { std::string RelativeInformation::GetLogHeader() const { std::string str_tmp = ""; - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector("sat" + std::to_string(target_sat_id) + " pos from sat" + std::to_string(reference_sat_id), "i", "m", 3); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector("sat" + std::to_string(target_spacecraft_id) + " pos from sat" + std::to_string(reference_spacecraft_id), "i", "m", 3); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector("sat" + std::to_string(target_sat_id) + " velocity from sat" + std::to_string(reference_sat_id), "i", "m/s", 3); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += + WriteVector("sat" + std::to_string(target_spacecraft_id) + " velocity from sat" + std::to_string(reference_spacecraft_id), "i", "m/s", 3); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector("sat" + std::to_string(target_sat_id) + " pos from sat" + std::to_string(reference_sat_id), "rtn", "m", 3); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector("sat" + std::to_string(target_spacecraft_id) + " pos from sat" + std::to_string(reference_spacecraft_id), "rtn", "m", 3); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector("sat" + std::to_string(target_sat_id) + " velocity from sat" + std::to_string(reference_sat_id), "rtn", "m/s", 3); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += + WriteVector("sat" + std::to_string(target_spacecraft_id) + " velocity from sat" + std::to_string(reference_spacecraft_id), "rtn", "m/s", 3); } } @@ -74,27 +80,27 @@ std::string RelativeInformation::GetLogHeader() const { std::string RelativeInformation::GetLogValue() const { std::string str_tmp = ""; - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector(GetRelativePosition_i_m(target_sat_id, reference_sat_id)); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector(GetRelativePosition_i_m(target_spacecraft_id, reference_spacecraft_id)); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector(GetRelativeVelocity_i_m_s(target_sat_id, reference_sat_id)); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector(GetRelativeVelocity_i_m_s(target_spacecraft_id, reference_spacecraft_id)); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector(GetRelativePosition_rtn_m(target_sat_id, reference_sat_id)); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector(GetRelativePosition_rtn_m(target_spacecraft_id, reference_spacecraft_id)); } } - for (size_t target_sat_id = 0; target_sat_id < dynamics_database_.size(); target_sat_id++) { - for (size_t reference_sat_id = 0; reference_sat_id < target_sat_id; reference_sat_id++) { - str_tmp += WriteVector(GetRelativeVelocity_rtn_m_s(target_sat_id, reference_sat_id)); + for (size_t target_spacecraft_id = 0; target_spacecraft_id < dynamics_database_.size(); target_spacecraft_id++) { + for (size_t reference_spacecraft_id = 0; reference_spacecraft_id < target_spacecraft_id; reference_spacecraft_id++) { + str_tmp += WriteVector(GetRelativeVelocity_rtn_m_s(target_spacecraft_id, reference_spacecraft_id)); } } @@ -103,40 +109,40 @@ std::string RelativeInformation::GetLogValue() const { void RelativeInformation::LogSetup(Logger& logger) { logger.AddLogList(this); } -libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int target_sat_id, const int reference_sat_id) { +libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id) { // Observer SC Body frame(obs_sat) -> ECI frame(i) - Quaternion q_reference_i2b = dynamics_database_.at(reference_sat_id)->GetAttitude().GetQuaternion_i2b(); + Quaternion q_reference_i2b = dynamics_database_.at(reference_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); Quaternion q_reference_b2i = q_reference_i2b.Conjugate(); // ECI frame(i) -> Target SC body frame(main_sat) - Quaternion q_target_i2b = dynamics_database_.at(target_sat_id)->GetAttitude().GetQuaternion_i2b(); + Quaternion q_target_i2b = dynamics_database_.at(target_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); return q_target_i2b * q_reference_b2i; } -libra::Vector<3> RelativeInformation::CalcRelativePosition_rtn_m(const int target_sat_id, const int reference_sat_id) { - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); +libra::Vector<3> RelativeInformation::CalcRelativePosition_rtn_m(const int target_spacecraft_id, const int reference_spacecraft_id) { + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetPosition_i_m(); libra::Vector<3> relative_pos_i = target_sat_pos_i - reference_sat_pos_i; // RTN frame for the reference satellite - libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternion_i2lvlh(); + libra::Quaternion q_i2rtn = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().CalcQuaternion_i2lvlh(); libra::Vector<3> relative_pos_rtn = q_i2rtn.FrameConversion(relative_pos_i); return relative_pos_rtn; } -libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int target_sat_id, const int reference_sat_id) { - libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetPosition_i_m(); - libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetPosition_i_m(); +libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int target_spacecraft_id, const int reference_spacecraft_id) { + libra::Vector<3> target_sat_pos_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetPosition_i_m(); + libra::Vector<3> reference_sat_pos_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetPosition_i_m(); libra::Vector<3> relative_pos_i = target_sat_pos_i - reference_sat_pos_i; // RTN frame for the reference satellite - libra::Quaternion q_i2rtn = dynamics_database_.at(reference_sat_id)->GetOrbit().CalcQuaternion_i2lvlh(); + libra::Quaternion q_i2rtn = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().CalcQuaternion_i2lvlh(); // Rotation vector of RTN frame - libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_sat_id)->GetOrbit().GetVelocity_i_m_s(); - libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_sat_id)->GetOrbit().GetVelocity_i_m_s(); + libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); + libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> rot_vec_rtn_i = cross(reference_sat_pos_i, reference_sat_vel_i); double r2_ref = CalcNorm(reference_sat_pos_i) * CalcNorm(reference_sat_pos_i); rot_vec_rtn_i /= r2_ref; @@ -148,10 +154,10 @@ libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int tar void RelativeInformation::ResizeLists() { size_t size = dynamics_database_.size(); - rel_pos_list_i_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); - rel_vel_list_i_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); - rel_distance_list_m_.assign(size, std::vector(size, 0.0)); - rel_pos_list_rtn_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); - rel_vel_list_rtn_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); - rel_att_quaternion_list_.assign(size, std::vector(size, libra::Quaternion(0, 0, 0, 1))); + relative_position_list_i_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); + relative_velocity_list_i_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); + relative_distance_list_m_.assign(size, std::vector(size, 0.0)); + relative_position_list_rtn_m_.assign(size, std::vector>(size, libra::Vector<3>(0))); + relative_velocity_list_rtn_m_s_.assign(size, std::vector>(size, libra::Vector<3>(0))); + relative_attitude_quaternion_list_.assign(size, std::vector(size, libra::Quaternion(0, 0, 0, 1))); } diff --git a/src/simulation/multiple_spacecraft/relative_information.hpp b/src/simulation/multiple_spacecraft/relative_information.hpp index 5dcea0f8a..5d950b679 100644 --- a/src/simulation/multiple_spacecraft/relative_information.hpp +++ b/src/simulation/multiple_spacecraft/relative_information.hpp @@ -70,99 +70,99 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativeAttitudeQuaternion * @brief Return relative attitude quaternion of the target spacecraft with respect to the reference spacecraft - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline libra::Quaternion GetRelativeAttitudeQuaternion(const int target_sat_id, const int reference_sat_id) const { - return rel_att_quaternion_list_[target_sat_id][reference_sat_id]; + inline libra::Quaternion GetRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_attitude_quaternion_list_[target_spacecraft_id][reference_spacecraft_id]; } /** * @fn GetRelativePosition_i_m * @brief Return relative position of the target spacecraft with respect to the reference spacecraft in the inertial frame and unit [m] - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline libra::Vector<3> GetRelativePosition_i_m(const int target_sat_id, const int reference_sat_id) const { - return rel_pos_list_i_m_[target_sat_id][reference_sat_id]; + inline libra::Vector<3> GetRelativePosition_i_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id]; } /** * @fn GetRelativeVelocity_i_m * @brief Return relative velocity of the target spacecraft with respect to the reference spacecraft in the inertial frame and unit [m] - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline libra::Vector<3> GetRelativeVelocity_i_m_s(const int target_sat_id, const int reference_sat_id) const { - return rel_vel_list_i_m_s_[target_sat_id][reference_sat_id]; + inline libra::Vector<3> GetRelativeVelocity_i_m_s(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_velocity_list_i_m_s_[target_spacecraft_id][reference_spacecraft_id]; } /** * @fn GetRelativeDistance_m * @brief Return relative distance between the target spacecraft and the reference spacecraft in unit [m] - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline double GetRelativeDistance_m(const int target_sat_id, const int reference_sat_id) const { - return rel_distance_list_m_[target_sat_id][reference_sat_id]; + inline double GetRelativeDistance_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_distance_list_m_[target_spacecraft_id][reference_spacecraft_id]; }; /** * @fn GetRelativePosition_rtn_m * @brief Return relative position of the target spacecraft with respect to the reference spacecraft in the RTN frame of the reference spacecraft * and unit [m] - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline libra::Vector<3> GetRelativePosition_rtn_m(const int target_sat_id, const int reference_sat_id) const { - return rel_pos_list_rtn_m_[target_sat_id][reference_sat_id]; + inline libra::Vector<3> GetRelativePosition_rtn_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_position_list_rtn_m_[target_spacecraft_id][reference_spacecraft_id]; } /** * @fn GetRelativeVelocity_rtn_m_s * @brief Return relative velocity of the target spacecraft with respect to the reference spacecraft in the RTN frame of the reference spacecraft * and unit [m] - * @params [in] target_sat_id: ID of target spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of target spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - inline libra::Vector<3> GetRelativeVelocity_rtn_m_s(const int target_sat_id, const int reference_sat_id) const { - return rel_vel_list_rtn_m_s_[target_sat_id][reference_sat_id]; + inline libra::Vector<3> GetRelativeVelocity_rtn_m_s(const int target_spacecraft_id, const int reference_spacecraft_id) const { + return relative_velocity_list_rtn_m_s_[target_spacecraft_id][reference_spacecraft_id]; } /** * @fn GetReferenceSatDynamics * @brief Return the dynamics information of a spacecraft * and unit [m] - * @params [in] target_sat_id: ID of the spacecraft + * @params [in] target_spacecraft_id: ID of the spacecraft */ - inline const Dynamics* GetReferenceSatDynamics(const int reference_sat_id) const { return dynamics_database_.at(reference_sat_id); }; + inline const Dynamics* GetReferenceSatDynamics(const int reference_spacecraft_id) const { return dynamics_database_.at(reference_spacecraft_id); }; private: std::map dynamics_database_; //!< Dynamics database of all spacecraft - std::vector>> rel_pos_list_i_m_; //!< Relative position list in the inertial frame in unit [m] - std::vector>> rel_vel_list_i_m_s_; //!< Relative velocity list in the inertial frame in unit [m/s] - std::vector>> rel_pos_list_rtn_m_; //!< Relative position list in the RTN frame in unit [m] - std::vector>> rel_vel_list_rtn_m_s_; //!< Relative velocity list in the RTN frame in unit [m/s] - std::vector> rel_distance_list_m_; //!< Relative distance list in unit [m] - std::vector> rel_att_quaternion_list_; //!< Relative attitude quaternion list + std::vector>> relative_position_list_i_m_; //!< Relative position list in the inertial frame in unit [m] + std::vector>> relative_velocity_list_i_m_s_; //!< Relative velocity list in the inertial frame in unit [m/s] + std::vector>> relative_position_list_rtn_m_; //!< Relative position list in the RTN frame in unit [m] + std::vector>> relative_velocity_list_rtn_m_s_; //!< Relative velocity list in the RTN frame in unit [m/s] + std::vector> relative_distance_list_m_; //!< Relative distance list in unit [m] + std::vector> relative_attitude_quaternion_list_; //!< Relative attitude quaternion list /** * @fn CalcRelativeAttitudeQuaternion * @brief Calculate and return the relative attitude quaternion - * @params [in] target_sat_id: ID of the spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of the spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - libra::Quaternion CalcRelativeAttitudeQuaternion(const int target_sat_id, const int reference_sat_id); + libra::Quaternion CalcRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id); /** * @fn CalcRelativePosition_rtn_m * @brief Calculate and return the relative position in RTN frame - * @params [in] target_sat_id: ID of the spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of the spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - libra::Vector<3> CalcRelativePosition_rtn_m(const int target_sat_id, const int reference_sat_id); + libra::Vector<3> CalcRelativePosition_rtn_m(const int target_spacecraft_id, const int reference_spacecraft_id); /** * @fn CalcRelativeVelocity_rtn_m_s * @brief Calculate and return the relative velocity in RTN frame - * @params [in] target_sat_id: ID of the spacecraft - * @params [in] reference_sat_id: ID of reference spacecraft + * @params [in] target_spacecraft_id: ID of the spacecraft + * @params [in] reference_spacecraft_id: ID of reference spacecraft */ - libra::Vector<3> CalcRelativeVelocity_rtn_m_s(const int target_sat_id, const int reference_sat_id); + libra::Vector<3> CalcRelativeVelocity_rtn_m_s(const int target_spacecraft_id, const int reference_spacecraft_id); /** * @fn ResizeLists From 6e53a2cc9dbc51ac372a0214db11546ff0352d36 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:31:48 +0100 Subject: [PATCH 0906/1086] Fix class name --- .../inter_spacecraft_communication.cpp | 4 ++-- .../inter_spacecraft_communication.hpp | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp index da0481966..300e8b4d5 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp @@ -7,6 +7,6 @@ #include -InterSatComm::InterSatComm(const SimulationConfig* simulation_configuration) { UNUSED(simulation_configuration); } +InterSpacecraftCommunication::InterSpacecraftCommunication(const SimulationConfig* simulation_configuration) { UNUSED(simulation_configuration); } -InterSatComm::~InterSatComm() {} +InterSpacecraftCommunication::~InterSpacecraftCommunication() {} diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp index 017e5b0fd..44ba54869 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp @@ -9,21 +9,21 @@ #include "../simulation_configuration.hpp" /** - * @class InterSatComm + * @class InterSpacecraftCommunication * @brief Base class of inter satellite communication */ -class InterSatComm { +class InterSpacecraftCommunication { public: /** - * @fn InterSatComm + * @fn InterSpacecraftCommunication * @brief Constructor */ - InterSatComm(const SimulationConfig* simulation_configuration); + InterSpacecraftCommunication(const SimulationConfig* simulation_configuration); /** - * @fn ~InterSatComm + * @fn ~InterSpacecraftCommunication * @brief Destructor */ - ~InterSatComm(); + ~InterSpacecraftCommunication(); private: }; From 6d57676228a7cdd85980467d58ca53fd884b88f6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:35:20 +0100 Subject: [PATCH 0907/1086] Remove using --- .../monte_carlo_simulation/simulation_object.cpp | 2 +- .../monte_carlo_simulation/simulation_object.hpp | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index 464d8fd90..f3ad1345c 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -36,6 +36,6 @@ void SimulationObject::GetInitParameterDouble(const MCSimExecutor& mc_sim, std:: mc_sim.GetInitParameterDouble(name_, ip_name, dst); } -void SimulationObject::GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, Quaternion& dst_quat) const { +void SimulationObject::GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, libra::Quaternion& dst_quat) const { mc_sim.GetInitParameterQuaternion(name_, ip_name, dst_quat); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index ef3d3b11f..9191d5196 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -16,8 +16,6 @@ #include "initialize_monte_carlo_parameters.hpp" #include "monte_carlo_simulation_executor.hpp" -using libra::Vector; - /** * @class SimulationObject * @brief Class to manage randomization of variables for Monte-Carlo simulation @@ -41,7 +39,7 @@ class SimulationObject { * @brief Get randomized vector value and store it in dst_vec */ template - void GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, Vector& dst_vec) const; + void GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, libra::Vector& dst_vec) const; /** * @fn GetInitParameterDouble @@ -53,7 +51,7 @@ class SimulationObject { * @fn GetInitParameterQuaternion * @brief Get randomized quaternion and store it in dst_quat */ - void GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, Quaternion& dst_quat) const; + void GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, libra::Quaternion& dst_quat) const; /** * @fn SetParameters @@ -77,7 +75,7 @@ class SimulationObject { * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, Vector& dst_vec) const { +void SimulationObject::GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, libra::Vector& dst_vec) const { mc_sim.GetInitParameterVec(name_, ip_name, dst_vec); } From 406d08587fbd5afdd37c824b5307760a3139d69b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:38:56 +0100 Subject: [PATCH 0908/1086] Fix function argument names --- src/simulation/case/simulation_case.cpp | 6 +-- src/simulation/case/simulation_case.hpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 42 +++++++++---------- .../initialize_monte_carlo_parameters.hpp | 22 +++++----- .../initialize_monte_carlo_simulation.cpp | 10 ++--- .../monte_carlo_simulation_executor.cpp | 12 +++--- .../monte_carlo_simulation_executor.hpp | 12 +++--- .../simulation_object.cpp | 25 +++++------ .../simulation_object.hpp | 23 +++++----- 9 files changed, 78 insertions(+), 76 deletions(-) diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 2df8cd305..86140ffbd 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -24,14 +24,14 @@ SimulationCase::SimulationCase(std::string ini_base) { sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); global_environment_ = new GlobalEnvironment(&sim_config_); } -SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, const std::string log_path) { +SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& monte_carlo_simulator, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); const char* section = "SIMULATION_SETTINGS"; sim_config_.initialize_base_file_name_ = ini_base; // Log for Monte Carlo Simulation - std::string log_file_name = "default" + std::to_string(mc_sim.GetNumOfExecutionsDone()) + ".csv"; + std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumOfExecutionsDone()) + ".csv"; // ToDo: Consider that `enable_inilog = false` is fine or not? - sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, mc_sim.LogHistory()); + sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, monte_carlo_simulator.LogHistory()); sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 0ef3738d3..93015f9b1 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -28,7 +28,7 @@ class SimulationCase : public ILoggable { * @fn SimulationCase * @brief Constructor for Monte-Carlo Simulation */ - SimulationCase(std::string ini_base, const MCSimExecutor& mc_sim, std::string log_path); + SimulationCase(std::string ini_base, const MCSimExecutor& monte_carlo_simulator, std::string log_path); /** * @fn ~SimulationCase * @brief Destructor diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index ed4dcde0f..b5bf7d64e 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -36,28 +36,28 @@ void InitParameter::SetSeed(unsigned long seed, bool is_deterministic) { } } -void InitParameter::GetDouble(double& dst) const { +void InitParameter::GetDouble(double& destination) const { if (rnd_type_ == NoRandomization) { ; } else if (1 > val_.size()) { throw "Too few randomization configuration parameters."; } else { - dst = val_[0]; + destination = val_[0]; } } -void InitParameter::GetQuaternion(Quaternion& dst_quat) const { +void InitParameter::GetQuaternion(Quaternion& destination) const { if (rnd_type_ == NoRandomization) { ; } else if (4 > val_.size()) { throw "Too few randomization configuration parameters."; } else { for (int i = 0; i < 4; i++) { - dst_quat[i] = val_[i]; + destination[i] = val_[i]; } } - dst_quat.Normalize(); + destination.Normalize(); } void InitParameter::Randomize() { @@ -116,12 +116,12 @@ void InitParameter::gen_CartesianNormal() { } } -void InitParameter::get_CircularNormalUniform(Vector<2>& dst, double r_mean, double r_sigma, double theta_min, double theta_max) { +void InitParameter::get_CircularNormalUniform(Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = InitParameter::Uniform_1d(theta_min, theta_max); - dst[0] = r * cos(theta); - dst[1] = r * sin(theta); + destination[0] = r * cos(theta); + destination[1] = r * sin(theta); } void InitParameter::gen_CircularNormalUniform() { @@ -138,12 +138,12 @@ void InitParameter::gen_CircularNormalUniform() { } } -void InitParameter::get_CircularNormalNormal(Vector<2>& dst, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { +void InitParameter::get_CircularNormalNormal(Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { // r and θ follow normal distribution in Circular frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = InitParameter::Normal_1d(theta_mean, theta_sigma); - dst[0] = r * cos(theta); - dst[1] = r * sin(theta); + destination[0] = r * cos(theta); + destination[1] = r * sin(theta); } void InitParameter::gen_CircularNormalNormal() { @@ -160,15 +160,15 @@ void InitParameter::gen_CircularNormalNormal() { } } -void InitParameter::get_SphericalNormalUniformUniform(Vector<3>& dst, double r_mean, double r_sigma, double theta_min, double theta_max, +void InitParameter::get_SphericalNormalUniformUniform(Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitParameter::Uniform_1d(0.0, 1.0)); double phi = InitParameter::Uniform_1d(phi_min, phi_max); - dst[0] = r * sin(theta) * cos(phi); - dst[1] = r * sin(theta) * sin(phi); - dst[2] = r * cos(theta); + destination[0] = r * sin(theta) * cos(phi); + destination[1] = r * sin(theta) * sin(phi); + destination[2] = r * cos(theta); } void InitParameter::gen_SphericalNormalUniformUniform() { @@ -186,7 +186,7 @@ void InitParameter::gen_SphericalNormalUniformUniform() { } } -void InitParameter::get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& mean_vec) { +void InitParameter::get_SphericalNormalNormal(Vector<3>& destination, const Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] Vector<3> mean_vec_dir; mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction @@ -212,7 +212,7 @@ void InitParameter::get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& m ret_vec = InitParameter::Normal_1d(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { - dst[i] = ret_vec[i]; + destination[i] = ret_vec[i]; } } @@ -233,7 +233,7 @@ void InitParameter::gen_SphericalNormalNormal() { } } -void InitParameter::get_QuaternionUniform(Quaternion& dst) { +void InitParameter::get_QuaternionUniform(Quaternion& destination) { // Perfectly Randomized Quaternion Vector<3> x_axis(0.0); x_axis[0] = 1.0; @@ -261,7 +261,7 @@ void InitParameter::get_QuaternionUniform(Quaternion& dst) { Quaternion ret_q = first_cnv * second_cnv; for (int i = 0; i < 4; i++) { - dst[i] = ret_q[i]; + destination[i] = ret_q[i]; } } @@ -276,7 +276,7 @@ void InitParameter::gen_QuaternionUniform() { } } -void InitParameter::get_QuaternionNormal(Quaternion& dst, double theta_sigma) { +void InitParameter::get_QuaternionNormal(Quaternion& destination, double theta_sigma) { // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere Vector<3> rot_axis; @@ -290,7 +290,7 @@ void InitParameter::get_QuaternionNormal(Quaternion& dst, double theta_sigma) { Quaternion ret_q(rot_axis, rotation_angle); for (int i = 0; i < 4; i++) { - dst[i] = ret_q[i]; + destination[i] = ret_q[i]; } } diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index fabf51551..f539b7e2b 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -63,17 +63,17 @@ class InitParameter { * @brief Get randomized vector value results */ template - void GetVec(Vector& dst_vec) const; + void GetVec(Vector& destination) const; /** * @fn GetQuaternion * @brief Get randomized quaternion results */ - void GetQuaternion(Quaternion& dst_quat) const; + void GetQuaternion(Quaternion& destination) const; /** * @fn GetDouble * @brief Get randomized value results */ - void GetDouble(double& dst) const; + void GetDouble(double& destination) const; // Calculation /** @@ -177,33 +177,33 @@ class InitParameter { * @fn get_CircularNormalUniform * @brief Calculate randomized value with CircularNormalUniform mode */ - void get_CircularNormalUniform(Vector<2>& dst, double r_mean, double r_sigma, double theta_min, double theta_max); + void get_CircularNormalUniform(Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max); /** * @fn get_CircularNormalNormal * @brief Calculate randomized value with CircularNormalNormal mode */ - void get_CircularNormalNormal(Vector<2>& dst, double r_mean, double r_sigma, double theta_mean, double theta_sigma); + void get_CircularNormalNormal(Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma); /** * @fn get_SphericalNormalUniformUniform * @brief Calculate randomized value with SphericalNormalUniformUniform mode */ - void get_SphericalNormalUniformUniform(Vector<3>& dst, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, + void get_SphericalNormalUniformUniform(Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, double phi_max); /** * @fn get_SphericalNormalNormal * @brief Calculate randomized value with SphericalNormalNormal mode */ - void get_SphericalNormalNormal(Vector<3>& dst, const Vector<3>& mean_vec); + void get_SphericalNormalNormal(Vector<3>& destination, const Vector<3>& mean_vec); /** * @fn get_QuaternionUniform * @brief Calculate randomized value with QuaternionUniform mode */ - void get_QuaternionUniform(Quaternion& dst); + void get_QuaternionUniform(Quaternion& destination); /** * @fn get_QuaternionNormal * @brief Calculate randomized value with QuaternionNormal mode */ - void get_QuaternionNormal(Quaternion& dst, double theta_sigma); + void get_QuaternionNormal(Quaternion& destination, double theta_sigma); }; template @@ -221,14 +221,14 @@ void InitParameter::SetRandomConfig(const Vector& mean_or_min, cons } template -void InitParameter::GetVec(Vector& dst_vec) const { +void InitParameter::GetVec(Vector& destination) const { if (rnd_type_ == NoRandomization) { ; } else if (NumElement > val_.size()) { throw "Too few randomization configuration parameters."; } else { for (size_t i = 0; i < NumElement; i++) { - dst_vec[i] = val_[i]; + destination[i] = val_[i]; } } } diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index a3ebc82aa..1c5772ee3 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -16,13 +16,13 @@ MCSimExecutor* InitMCSim(std::string file_name) { unsigned long long total_num_of_executions = ini_file.ReadInt(section, "number_of_executions"); - MCSimExecutor* mc_sim = new MCSimExecutor(total_num_of_executions); + MCSimExecutor* monte_carlo_simulator = new MCSimExecutor(total_num_of_executions); bool enable = ini_file.ReadEnable(section, "monte_carlo_enable"); - mc_sim->Enable(enable); + monte_carlo_simulator->Enable(enable); bool log_history = ini_file.ReadEnable(section, "log_enable"); - mc_sim->LogHistory(log_history); + monte_carlo_simulator->LogHistory(log_history); section = "MONTE_CARLO_RANDOMIZATION"; std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "parameter"); @@ -88,8 +88,8 @@ MCSimExecutor* InitMCSim(std::string file_name) { ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); // Write randomize setting - mc_sim->AddInitParameter(so_str, ip_str, mean_or_min, sigma_or_max, rnd_type); + monte_carlo_simulator->AddInitParameter(so_str, ip_str, mean_or_min, sigma_or_max, rnd_type); } - return mc_sim; + return monte_carlo_simulator; } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 4ca123337..03f3fb868 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -31,28 +31,28 @@ void MCSimExecutor::AtTheEndOfEachCase() { num_of_executions_done_++; } -void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, double& dst) const { +void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, double& destination) const { if (!enabled_) return; { string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) - return; // return without any update of dst + return; // return without any update of destination } else { - ip_list_.at(name)->GetDouble(dst); // cannot use operator[] since it is const map + ip_list_.at(name)->GetDouble(destination); // cannot use operator[] since it is const map } } } -void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, Quaternion& dst_quat) const { +void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, Quaternion& destination) const { if (!enabled_) return; { string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) - return; // return without any update of dst + return; // return without any update of destination } else { - ip_list_.at(name)->GetQuaternion(dst_quat); // cannot use operator[] since it is const map + ip_list_.at(name)->GetQuaternion(destination); // cannot use operator[] since it is const map } } } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index d795d8dd7..e9f315810 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -84,17 +84,17 @@ class MCSimExecutor { * @brief Get randomized vector value and store it in dest_vec */ template - void GetInitParameterVec(std::string so_name, std::string ip_name, Vector& dst_vec) const; + void GetInitParameterVec(std::string so_name, std::string ip_name, Vector& destination) const; /** * @fn GetInitParameterDouble * @brief Get randomized value and store it in dest */ - void GetInitParameterDouble(std::string so_name, std::string ip_name, double& dst) const; + void GetInitParameterDouble(std::string so_name, std::string ip_name, double& destination) const; /** * @fn GetInitParameterQuaternion * @brief Get randomized quaternion and store it in dest_quat */ - void GetInitParameterQuaternion(std::string so_name, std::string ip_name, Quaternion& dst_quat) const; + void GetInitParameterQuaternion(std::string so_name, std::string ip_name, Quaternion& destination) const; // Calculation /** @@ -150,14 +150,14 @@ bool MCSimExecutor::LogHistory() const { void MCSimExecutor::LogHistory(bool set) { log_history_ = set; } template -void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, Vector& dst_vec) const { +void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, Vector& destination) const { if (!enabled_) return; std::string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) - return; // return without update the dst_vec + return; // return without update the destination } else { - ip_list_.at(name)->GetVec(dst_vec); // cannot use operator[] since it is const map + ip_list_.at(name)->GetVec(destination); // cannot use operator[] since it is const map } } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index f3ad1345c..768120d92 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -5,15 +5,15 @@ #include "simulation_object.hpp" -std::map SimulationObject::so_list_; +std::map SimulationObject::ojbect_list_; SimulationObject::SimulationObject(std::string name) : name_(name) { // Check the name is already registered in so_list - std::map::iterator itr = SimulationObject::so_list_.find(name); + std::map::iterator itr = SimulationObject::ojbect_list_.find(name); - if (itr == SimulationObject::so_list_.end()) { + if (itr == SimulationObject::ojbect_list_.end()) { // Register itself in so_list if it is not registered yet - SimulationObject::so_list_[name] = this; + SimulationObject::ojbect_list_[name] = this; } else { // If it is already registered in so_list, throw error. It should be deleted in the finalize phase of previous case. // Or there is a possibility that the same name SimulationObjects are registered in the list. @@ -23,19 +23,20 @@ SimulationObject::SimulationObject(std::string name) : name_(name) { SimulationObject::~SimulationObject() { // Remove itself from so_list - SimulationObject::so_list_.erase(name_); + SimulationObject::ojbect_list_.erase(name_); } -void SimulationObject::SetAllParameters(const MCSimExecutor& mc_sim) { - for (auto so : SimulationObject::so_list_) { - so.second->SetParameters(mc_sim); +void SimulationObject::SetAllParameters(const MCSimExecutor& monte_carlo_simulator) { + for (auto so : SimulationObject::ojbect_list_) { + so.second->SetParameters(monte_carlo_simulator); } } -void SimulationObject::GetInitParameterDouble(const MCSimExecutor& mc_sim, std::string ip_name, double& dst) const { - mc_sim.GetInitParameterDouble(name_, ip_name, dst); +void SimulationObject::GetInitParameterDouble(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const { + monte_carlo_simulator.GetInitParameterDouble(name_, ip_name, destination); } -void SimulationObject::GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, libra::Quaternion& dst_quat) const { - mc_sim.GetInitParameterQuaternion(name_, ip_name, dst_quat); +void SimulationObject::GetInitParameterQuaternion(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, + libra::Quaternion& destination) const { + monte_carlo_simulator.GetInitParameterQuaternion(name_, ip_name, destination); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 9191d5196..f3c040f9a 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -36,38 +36,38 @@ class SimulationObject { /** * @fn GetInitParameterVec - * @brief Get randomized vector value and store it in dst_vec + * @brief Get randomized vector value and store it in destination */ template - void GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, libra::Vector& dst_vec) const; + void GetInitParameterVec(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, libra::Vector& destination) const; /** * @fn GetInitParameterDouble - * @brief Get randomized value and store it in dst + * @brief Get randomized value and store it in destination */ - void GetInitParameterDouble(const MCSimExecutor& mc_sim, std::string ip_name, double& dst) const; + void GetInitParameterDouble(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; /** * @fn GetInitParameterQuaternion - * @brief Get randomized quaternion and store it in dst_quat + * @brief Get randomized quaternion and store it in destination */ - void GetInitParameterQuaternion(const MCSimExecutor& mc_sim, std::string ip_name, libra::Quaternion& dst_quat) const; + void GetInitParameterQuaternion(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, libra::Quaternion& destination) const; /** * @fn SetParameters * @brief Virtual function to set the randomized results to target variables */ - virtual void SetParameters(const MCSimExecutor& mc_sim) = 0; + virtual void SetParameters(const MCSimExecutor& monte_carlo_simulator) = 0; /** * @fn SetAllParameters * @brief Execute all SetParameter function for all SimulationObject instance */ - static void SetAllParameters(const MCSimExecutor& mc_sim); + static void SetAllParameters(const MCSimExecutor& monte_carlo_simulator); private: std::string name_; //!< Name to distinguish the target variable in initialize file for Monte-Carlo simulation - static std::map so_list_; //!< list of objects with simulation parameters + static std::map ojbect_list_; //!< list of objects with simulation parameters }; /** @@ -75,8 +75,9 @@ class SimulationObject { * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitParameterVec(const MCSimExecutor& mc_sim, std::string ip_name, libra::Vector& dst_vec) const { - mc_sim.GetInitParameterVec(name_, ip_name, dst_vec); +void SimulationObject::GetInitParameterVec(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, + libra::Vector& destination) const { + monte_carlo_simulator.GetInitParameterVec(name_, ip_name, destination); } #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ From cc9b4c4260d92da27de6a46f02484d90b3af446f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:53:00 +0100 Subject: [PATCH 0909/1086] Remove using --- src/components/real/aocs/gnss_receiver.cpp | 2 +- src/components/real/aocs/gyro_sensor.cpp | 2 +- .../real/aocs/initialize_gnss_receiver.cpp | 6 +- .../real/aocs/initialize_gyro_sensor.cpp | 4 +- .../real/aocs/initialize_magnetometer.cpp | 4 +- .../real/aocs/initialize_magnetorquer.cpp | 30 ++++----- .../real/aocs/initialize_star_sensor.cpp | 4 +- src/components/real/aocs/magnetometer.cpp | 4 +- src/components/real/aocs/magnetorquer.cpp | 4 +- src/components/real/aocs/star_sensor.cpp | 30 ++++----- src/components/real/aocs/star_sensor.hpp | 14 ++-- .../real/mission/initialize_telescope.cpp | 2 +- src/components/real/mission/telescope.cpp | 12 ++-- src/components/real/mission/telescope.hpp | 8 +-- .../real/propulsion/simple_thruster.cpp | 27 ++++---- src/dynamics/attitude/controlled_attitude.cpp | 8 +-- src/dynamics/attitude/controlled_attitude.hpp | 4 +- src/dynamics/attitude/initialize_attitude.cpp | 6 +- .../ground_station/ground_station.cpp | 8 +-- .../initialize_monte_carlo_parameters.cpp | 65 ++++++++++--------- .../initialize_monte_carlo_parameters.hpp | 29 ++++----- .../initialize_monte_carlo_simulation.cpp | 4 +- .../monte_carlo_simulation_executor.cpp | 2 +- .../monte_carlo_simulation_executor.hpp | 16 ++--- .../relative_information.cpp | 6 +- 25 files changed, 149 insertions(+), 152 deletions(-) diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index 6c29c1000..afb7d6996 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -51,7 +51,7 @@ void GnssReceiver::MainRoutine(const int time_count) { UNUSED(time_count); libra::Vector<3> pos_true_eci_ = dynamics_->GetOrbit().GetPosition_i_m(); - Quaternion quaternion_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); + libra::Quaternion quaternion_i2b = dynamics_->GetAttitude().GetQuaternion_i2b(); CheckAntenna(pos_true_eci_, quaternion_i2b); diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index 26ccb0948..cf5d2659e 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -6,7 +6,7 @@ #include "gyro_sensor.hpp" GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const Dynamics* dynamics) + const libra::Quaternion& quaternion_b2c, const Dynamics* dynamics) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), dynamics_(dynamics) {} GyroSensor::GyroSensor(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index e9befefa9..78f7fadae 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -11,12 +11,12 @@ typedef struct _gnssrecever_param { int prescaler; AntennaModel antenna_model; - Vector<3> antenna_pos_b; - Quaternion quaternion_b2c; + libra::Vector<3> antenna_pos_b; + libra::Quaternion quaternion_b2c; double half_width_rad; std::string gnss_id; int max_channel; - Vector<3> noise_standard_deviation_m; + libra::Vector<3> noise_standard_deviation_m; } GnssReceiverParam; GnssReceiverParam ReadGnssReceiverIni(const std::string file_name, const GnssSatellites* gnss_satellites, const int component_id) { diff --git a/src/components/real/aocs/initialize_gyro_sensor.cpp b/src/components/real/aocs/initialize_gyro_sensor.cpp index 7c676090a..588ebe587 100644 --- a/src/components/real/aocs/initialize_gyro_sensor.cpp +++ b/src/components/real/aocs/initialize_gyro_sensor.cpp @@ -15,7 +15,7 @@ GyroSensor InitGyroSensor(ClockGenerator* clock_generator, int sensor_id, const const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", quaternion_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; @@ -36,7 +36,7 @@ GyroSensor InitGyroSensor(ClockGenerator* clock_generator, PowerPort* power_port const std::string section_name = sensor_name + std::to_string(static_cast(sensor_id)); const char* GSection = section_name.c_str(); - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; gyro_conf.ReadQuaternion(GSection, "quaternion_b2c", quaternion_b2c); int prescaler = gyro_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; diff --git a/src/components/real/aocs/initialize_magnetometer.cpp b/src/components/real/aocs/initialize_magnetometer.cpp index 6fa42fba3..61bea49d8 100644 --- a/src/components/real/aocs/initialize_magnetometer.cpp +++ b/src/components/real/aocs/initialize_magnetometer.cpp @@ -17,7 +17,7 @@ Magnetometer InitMagetometer(ClockGenerator* clock_generator, int sensor_id, con int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor @@ -38,7 +38,7 @@ Magnetometer InitMagetometer(ClockGenerator* clock_generator, PowerPort* power_p int prescaler = magsensor_conf.ReadInt(MSSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; magsensor_conf.ReadQuaternion(MSSection, "quaternion_b2c", quaternion_b2c); // Sensor diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index 0e8b371af..c203d0135 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -25,24 +25,24 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, } } - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_magnetic_moment_c_Am2; + libra::Vector max_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_magnetic_moment_c_Am2; + libra::Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_noise_c_Am2_; + libra::Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); double random_walk_step_width_s = component_step_time_s * (double)prescaler; - Vector random_walk_standard_deviation_c_Am2; + libra::Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); - Vector random_walk_limit_c_Am2; + libra::Vector random_walk_limit_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); - Vector normal_random_standard_deviation_c_Am2; + libra::Vector normal_random_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); Magnetorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, @@ -61,7 +61,7 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_ int prescaler = magtorquer_conf.ReadInt(MTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - Vector sf_vec; + libra::Vector sf_vec; magtorquer_conf.ReadVector(MTSection, "scale_factor_c", sf_vec); libra::Matrix scale_factor; for (size_t i = 0; i < kMtqDimension; i++) { @@ -70,24 +70,24 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_ } } - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; magtorquer_conf.ReadQuaternion(MTSection, "quaternion_b2c", quaternion_b2c); - Vector max_magnetic_moment_c_Am2; + libra::Vector max_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "max_output_magnetic_moment_c_Am2", max_magnetic_moment_c_Am2); - Vector min_magnetic_moment_c_Am2; + libra::Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - Vector bias_noise_c_Am2_; + libra::Vector bias_noise_c_Am2_; magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); double random_walk_step_width_s = component_step_time_s * (double)prescaler; - Vector random_walk_standard_deviation_c_Am2; + libra::Vector random_walk_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_standard_deviation_c_Am2", random_walk_standard_deviation_c_Am2); - Vector random_walk_limit_c_Am2; + libra::Vector random_walk_limit_c_Am2; magtorquer_conf.ReadVector(MTSection, "random_walk_limit_c_Am2", random_walk_limit_c_Am2); - Vector normal_random_standard_deviation_c_Am2; + libra::Vector normal_random_standard_deviation_c_Am2; magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); // PowerPort diff --git a/src/components/real/aocs/initialize_star_sensor.cpp b/src/components/real/aocs/initialize_star_sensor.cpp index 4b86906c8..84f5b9016 100644 --- a/src/components/real/aocs/initialize_star_sensor.cpp +++ b/src/components/real/aocs/initialize_star_sensor.cpp @@ -20,7 +20,7 @@ StarSensor InitStarSensor(ClockGenerator* clock_generator, int sensor_id, const int prescaler = STT_conf.ReadInt(STTSection, "prescaler"); if (prescaler <= 1) prescaler = 1; double step_time_s = component_step_time_s * prescaler; - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); double standard_deviation_orthogonal_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); double standard_deviation_sight_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); @@ -54,7 +54,7 @@ StarSensor InitStarSensor(ClockGenerator* clock_generator, PowerPort* power_port if (prescaler <= 1) prescaler = 1; double step_time_s = component_step_time_s * prescaler; - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; STT_conf.ReadQuaternion(STTSection, "quaternion_b2c", quaternion_b2c); double standard_deviation_orthogonal_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_orthogonal_direction_rad"); double standard_deviation_sight_direction = STT_conf.ReadDouble(STTSection, "standard_deviation_sight_direction_rad"); diff --git a/src/components/real/aocs/magnetometer.cpp b/src/components/real/aocs/magnetometer.cpp index 7b4c9cc66..ecc4410c4 100644 --- a/src/components/real/aocs/magnetometer.cpp +++ b/src/components/real/aocs/magnetometer.cpp @@ -7,14 +7,14 @@ #include Magnetometer::Magnetometer(int prescaler, ClockGenerator* clock_generator, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator), Sensor(sensor_base), sensor_id_(sensor_id), quaternion_b2c_(quaternion_b2c), geomagnetic_field_(geomagnetic_field) {} Magnetometer::Magnetometer(int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, Sensor& sensor_base, const unsigned int sensor_id, - const Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) + const libra::Quaternion& quaternion_b2c, const GeomagneticField* geomagnetic_field) : Component(prescaler, clock_generator, power_port), Sensor(sensor_base), sensor_id_(sensor_id), diff --git a/src/components/real/aocs/magnetorquer.cpp b/src/components/real/aocs/magnetorquer.cpp index 23d0e4f86..7cbc1540a 100644 --- a/src/components/real/aocs/magnetorquer.cpp +++ b/src/components/real/aocs/magnetorquer.cpp @@ -10,7 +10,7 @@ #include #include -Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Quaternion& quaternion_b2c, +Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, const int component_id, const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, @@ -33,7 +33,7 @@ Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, } Magnetorquer::Magnetorquer(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, + const libra::Quaternion& quaternion_b2c, const libra::Matrix& scale_factor, const libra::Vector& max_magnetic_moment_c_Am2, const libra::Vector& min_magnetic_moment_c_Am2, const libra::Vector& bias_noise_c_Am2_, double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c_Am2, diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index b310b6664..66b532a48 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -66,21 +66,21 @@ StarSensor::StarSensor(const int prescaler, ClockGenerator* clock_generator, Pow } void StarSensor::Initialize() { - measured_quaternion_i2c_ = Quaternion(0.0, 0.0, 0.0, 1.0); + measured_quaternion_i2c_ = libra::Quaternion(0.0, 0.0, 0.0, 1.0); // Decide delay buffer size max_delay_ = int(output_delay_ * 2 / step_time_s_); if (max_delay_ <= 0) max_delay_ = 1; - vector temp(max_delay_); + vector temp(max_delay_); delay_buffer_ = temp; // Initialize delay buffer for (int i = 0; i < max_delay_; ++i) { delay_buffer_[i] = measured_quaternion_i2c_; } - sight_direction_c_ = Vector<3>(0.0); - first_orthogonal_direction_c = Vector<3>(0.0); - second_orthogonal_direction_c = Vector<3>(0.0); + sight_direction_c_ = libra::Vector<3>(0.0); + first_orthogonal_direction_c = libra::Vector<3>(0.0); + second_orthogonal_direction_c = libra::Vector<3>(0.0); sight_direction_c_[0] = 1.0; //(1,0,0)@Component coordinates, viewing direction first_orthogonal_direction_c[1] = 1.0; //(0,1,0)@Component coordinates, line-of-sight orthogonal direction second_orthogonal_direction_c[2] = 1.0; //(0,0,1)@Component coordinates, line-of-sight orthogonal direction @@ -111,8 +111,8 @@ void StarSensor::update(const LocalCelestialInformation* local_celestial_informa // Random noise on orthogonal direction of sight. Range [0:2pi] double rot = libra::tau * double(rotation_noise_); // Calc observation error on orthogonal direction of sight - Vector<3> rot_axis = cos(rot) * first_orthogonal_direction_c + sin(rot) * second_orthogonal_direction_c; - Quaternion q_ortho(rot_axis, orthogonal_direction_noise_); + libra::Vector<3> rot_axis = cos(rot) * first_orthogonal_direction_c + sin(rot) * second_orthogonal_direction_c; + libra::Quaternion q_ortho(rot_axis, orthogonal_direction_noise_); // Judge errors AllJudgement(local_celestial_information, attitude); @@ -137,8 +137,8 @@ void StarSensor::AllJudgement(const LocalCelestialInformation* local_celestial_i } int StarSensor::SunJudgement(const libra::Vector<3>& sun_b) { - Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); + libra::Quaternion q_c2b = quaternion_b2c_.Conjugate(); + libra::Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double sun_angle_rad = CalAngleVector_rad(sun_b, sight_b); if (sun_angle_rad < sun_forbidden_angle_rad_) return 1; @@ -147,8 +147,8 @@ int StarSensor::SunJudgement(const libra::Vector<3>& sun_b) { } int StarSensor::EarthJudgement(const libra::Vector<3>& earth_b) { - Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); + libra::Quaternion q_c2b = quaternion_b2c_.Conjugate(); + libra::Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge double earth_center_angle_rad = CalAngleVector_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight @@ -160,8 +160,8 @@ int StarSensor::EarthJudgement(const libra::Vector<3>& earth_b) { } int StarSensor::MoonJudgement(const libra::Vector<3>& moon_b) { - Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); + libra::Quaternion q_c2b = quaternion_b2c_.Conjugate(); + libra::Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double moon_angle_rad = CalAngleVector_rad(moon_b, sight_b); if (moon_angle_rad < moon_forbidden_angle_rad_) return 1; @@ -198,9 +198,9 @@ std::string StarSensor::GetLogValue() const { } double StarSensor::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector2) { - Vector<3> vect1_normal(vector1); + libra::Vector<3> vect1_normal(vector1); Normalize(vect1_normal); // Normalize Vector1 - Vector<3> vect2_normal(vector2); + libra::Vector<3> vect2_normal(vector2); Normalize(vect2_normal); // Normalize Vector2 double cosTheta = InnerProduct(vect1_normal, vect2_normal); // Calc cos value double theta_rad = acos(cosTheta); diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index 6ee12efe0..6b08791f7 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -120,13 +120,13 @@ class StarSensor : public Component, public ILoggable { libra::NormalRand sight_direction_noise_; //!< Random noise for sight direction // Delay emulation parameters - int max_delay_; //!< Max delay - std::vector delay_buffer_; //!< Buffer of quaternion for delay emulation - int buffer_position_; //!< Buffer position - double step_time_s_; //!< Step time for delay calculation [sec] - unsigned int output_delay_; //!< Output delay [0, max_delay_] [step_sec] - unsigned int output_interval_; //!< Output interval [step_sec] - std::size_t update_count_; //!< Output update counter + int max_delay_; //!< Max delay + std::vector delay_buffer_; //!< Buffer of quaternion for delay emulation + int buffer_position_; //!< Buffer position + double step_time_s_; //!< Step time for delay calculation [sec] + unsigned int output_delay_; //!< Output delay [0, max_delay_] [step_sec] + unsigned int output_interval_; //!< Output interval [step_sec] + std::size_t update_count_; //!< Output update counter // observation error parameters bool error_flag_; //!< Error flag. true: Error, false: No error diff --git a/src/components/real/mission/initialize_telescope.cpp b/src/components/real/mission/initialize_telescope.cpp index 87ec27616..977c6c548 100644 --- a/src/components/real/mission/initialize_telescope.cpp +++ b/src/components/real/mission/initialize_telescope.cpp @@ -28,7 +28,7 @@ Telescope InitTelescope(ClockGenerator* clock_generator, int sensor_id, const st strcat(TelescopeSection, cs); #endif - Quaternion quaternion_b2c; + libra::Quaternion quaternion_b2c; Telescope_conf.ReadQuaternion(TelescopeSection, "quaternion_b2c", quaternion_b2c); double sun_forbidden_angle_deg = Telescope_conf.ReadDouble(TelescopeSection, "sun_exclusion_angle_deg"); diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index fd63620fb..cc8c80e64 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -80,8 +80,8 @@ void Telescope::MainRoutine(int count) { } bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const double forbidden_angle) { - Quaternion q_c2b = quaternion_b2c_.Conjugate(); - Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); + libra::Quaternion q_c2b = quaternion_b2c_.Conjugate(); + libra::Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double angle_rad = libra::CalcAngleTwoVectors_rad(target_b, sight_b); if (angle_rad < forbidden_angle) { return true; @@ -89,8 +89,8 @@ bool Telescope::JudgeForbiddenAngle(const libra::Vector<3>& target_b, const doub return false; } -void Telescope::Observe(Vector<2>& position_image_sensor, const Vector<3, double> target_b) { - Vector<3, double> target_c = quaternion_b2c_.FrameConversion(target_b); +void Telescope::Observe(libra::Vector<2>& position_image_sensor, const libra::Vector<3, double> target_b) { + libra::Vector<3, double> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame @@ -110,8 +110,8 @@ void Telescope::ObserveStars() { int count = 0; // Counter for while loop while (star_list_in_sight.size() < number_of_logged_stars_) { - Vector<3> target_b = hipparcos_->GetStarDirection_b(count, quaternion_i2b); - Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); + libra::Vector<3> target_b = hipparcos_->GetStarDirection_b(count, quaternion_i2b); + libra::Vector<3> target_c = quaternion_b2c_.FrameConversion(target_b); double arg_x = atan2(target_c[2], target_c[0]); // Angle from X-axis on XZ plane in the component frame double arg_y = atan2(target_c[1], target_c[0]); // Angle from X-axis on XY plane in the component frame diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 3f7a83d33..cd66778a4 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -111,7 +111,7 @@ class Telescope : public Component, public ILoggable { * @param [out] position_image_sensor: Position on image sensor plane * @param [in] target_b: Direction vector of target on the body fixed frame */ - void Observe(Vector<2>& position_image_sensor, const Vector<3, double> target_b); + void Observe(libra::Vector<2>& position_image_sensor, const libra::Vector<3, double> target_b); /** * @fn ObserveStars * @brief Observe stars from Hipparcos catalogue @@ -135,9 +135,9 @@ class Telescope : public Component, public ILoggable { virtual std::string GetLogValue() const; // For debug ********************************************** - // Vector<3> sun_pos_c; - // Vector<3> earth_pos_c; - // Vector<3> moon_pos_c; + // libra::Vector<3> sun_pos_c; + // libra::Vector<3> earth_pos_c; + // libra::Vector<3> moon_pos_c; // double angle_sun; // double angle_earth; // double angle_moon; diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index 4e5412ce3..b5eaba08c 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -9,9 +9,10 @@ #include // Constructor -SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, const Vector<3> thruster_position_b_m, - const Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, - const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) +SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, const int component_id, + const libra::Vector<3> thruster_position_b_m, const libra::Vector<3> thrust_direction_b, const double max_magnitude_N, + const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, + const Dynamics* dynamics) : Component(prescaler, clock_generator), component_id_(component_id), thruster_position_b_m_(thruster_position_b_m), @@ -24,7 +25,7 @@ SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_genera } SimpleThruster::SimpleThruster(const int prescaler, ClockGenerator* clock_generator, PowerPort* power_port, const int component_id, - const Vector<3> thruster_position_b_m, const Vector<3> thrust_direction_b, const double max_magnitude_N, + const libra::Vector<3> thruster_position_b_m, const libra::Vector<3> thrust_direction_b, const double max_magnitude_N, const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad, const Structure* structure, const Dynamics* dynamics) : Component(prescaler, clock_generator, power_port), @@ -64,9 +65,9 @@ void SimpleThruster::CalcThrust() { output_thrust_b_N_ = mag * CalcThrustDirection(); } -void SimpleThruster::CalcTorque(const Vector<3> center_of_mass_b_m) { - Vector<3> vector_center2thruster = thruster_position_b_m_ - center_of_mass_b_m; - Vector<3> torque = OuterProduct(vector_center2thruster, output_thrust_b_N_); +void SimpleThruster::CalcTorque(const libra::Vector<3> center_of_mass_b_m) { + libra::Vector<3> vector_center2thruster = thruster_position_b_m_ - center_of_mass_b_m; + libra::Vector<3> torque = OuterProduct(vector_center2thruster, output_thrust_b_N_); output_torque_b_Nm_ = torque; } @@ -93,10 +94,10 @@ std::string SimpleThruster::GetLogValue() const { double SimpleThruster::CalcThrustMagnitude() { return duty_ * thrust_magnitude_max_N_; } -Vector<3> SimpleThruster::CalcThrustDirection() { - Vector<3> thrust_dir_b_true = thrust_direction_b_; +libra::Vector<3> SimpleThruster::CalcThrustDirection() { + libra::Vector<3> thrust_dir_b_true = thrust_direction_b_; if (direction_noise_standard_deviation_rad_ > 0.0 + DBL_EPSILON) { - Vector<3> ex; // Fixme: to use outer product to generate orthogonal vector + libra::Vector<3> ex; // Fixme: to use outer product to generate orthogonal vector ex[0] = 1.0; ex[1] = 0.0; ex[2] = 0.0; @@ -108,10 +109,10 @@ Vector<3> SimpleThruster::CalcThrustDirection() { make_axis_rot_rad = -libra::pi * (double)rand() / RAND_MAX; } - Quaternion make_axis_rot(thrust_dir_b_true, make_axis_rot_rad); - Vector<3> axis_rot = make_axis_rot.FrameConversion(ex); + libra::Quaternion make_axis_rot(thrust_dir_b_true, make_axis_rot_rad); + libra::Vector<3> axis_rot = make_axis_rot.FrameConversion(ex); - Quaternion err_rot(axis_rot, direction_random_noise_); // Generate error quaternion + libra::Quaternion err_rot(axis_rot, direction_random_noise_); // Generate error quaternion thrust_dir_b_true = err_rot.FrameConversion(thrust_dir_b_true); // Add error } diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index cc332ac54..23b061578 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -56,7 +56,7 @@ void ControlledAttitude::Initialize(void) { } void ControlledAttitude::Propagate(const double end_time_s) { - Vector<3> main_direction_i, sub_direction_i; + libra::Vector<3> main_direction_i, sub_direction_i; if (!is_calc_enabled_) return; if (main_mode_ == INERTIAL_STABILIZE) { @@ -75,8 +75,8 @@ void ControlledAttitude::Propagate(const double end_time_s) { return; } -Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { - Vector<3> direction; +libra::Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { + libra::Vector<3> direction; if (mode == SUN_POINTING) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); } else if (mode == EARTH_CENTER_POINTING) { @@ -98,7 +98,7 @@ void ControlledAttitude::PointingControl(const libra::Vector<3> main_direction_i // Calc DCM ECI->body libra::Matrix<3, 3> dcm_i2b = dcm_t2b * Transpose(dcm_t2i); // Convert to Quaternion - quaternion_i2b_ = Quaternion::ConvertFromDcm(dcm_i2b); + quaternion_i2b_ = libra::Quaternion::ConvertFromDcm(dcm_i2b); } libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_direction, const libra::Vector<3> sub_direction) { diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 52411f938..8ca018af1 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -53,7 +53,7 @@ class ControlledAttitude : public Attitude { * @param [in] orbit: Orbit * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const Quaternion quaternion_i2b, + ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const libra::Quaternion quaternion_i2b, const libra::Vector<3> main_target_direction_b, const libra::Vector<3> sub_target_direction_b, const libra::Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, const std::string& simulation_object_name = "Attitude"); @@ -78,7 +78,7 @@ class ControlledAttitude : public Attitude { * @fn SetQuaternion_i2t * @brief Set quaternion for INERTIAL_STABILIZE mode */ - inline void SetQuaternion_i2t(const Quaternion quaternion_i2t) { quaternion_i2b_ = quaternion_i2t; } + inline void SetQuaternion_i2t(const libra::Quaternion quaternion_i2t) { quaternion_i2b_ = quaternion_i2t; } /** * @fn SetMainTargetDirection_b * @brief Set main target direction on the body fixed frame diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 97bbeca92..0383b8c62 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -19,7 +19,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel // RK4 propagator libra::Vector<3> omega_b; ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); - Quaternion quaternion_i2b; + libra::Quaternion quaternion_i2b; ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); libra::Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); @@ -34,7 +34,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel AttitudeControlMode main_mode = ConvertStringToCtrlMode(main_mode_in); AttitudeControlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); - Quaternion quaternion_i2b; + libra::Quaternion quaternion_i2b; ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); libra::Vector<3> main_target_direction_b, sub_target_direction_b; ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); @@ -47,7 +47,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel libra::Vector<3> omega_b; ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); - Quaternion quaternion_i2b; + libra::Quaternion quaternion_i2b; ini_file.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); libra::Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 4dcb6393c..c074fae87 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -51,12 +51,12 @@ void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacec is_visible_[spacecraft.GetSpacecraftId()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); } -bool GroundStation::CalcIsVisible(const Vector<3> sc_pos_ecef_m) { - Quaternion q_ecef_to_ltc = gs_position_geo_.GetQuaternionXcxfToLtc(); +bool GroundStation::CalcIsVisible(const libra::Vector<3> sc_pos_ecef_m) { + libra::Quaternion q_ecef_to_ltc = gs_position_geo_.GetQuaternionXcxfToLtc(); - Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] + libra::Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] Normalize(sc_pos_ltc); - Vector<3> dir_gs_to_zenith = Vector<3>(0); + libra::Vector<3> dir_gs_to_zenith = libra::Vector<3>(0); dir_gs_to_zenith[2] = 1; // Judge the satellite position angle is over the minimum elevation diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index b5bf7d64e..62768f6ae 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -46,7 +46,7 @@ void InitParameter::GetDouble(double& destination) const { } } -void InitParameter::GetQuaternion(Quaternion& destination) const { +void InitParameter::GetQuaternion(libra::Quaternion& destination) const { if (rnd_type_ == NoRandomization) { ; } else if (4 > val_.size()) { @@ -116,7 +116,7 @@ void InitParameter::gen_CartesianNormal() { } } -void InitParameter::get_CircularNormalUniform(Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { +void InitParameter::get_CircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = InitParameter::Uniform_1d(theta_min, theta_max); @@ -129,7 +129,7 @@ void InitParameter::gen_CircularNormalUniform() { if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; } - Vector temp_vec; + libra::Vector temp_vec; get_CircularNormalUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); val_.clear(); @@ -138,7 +138,7 @@ void InitParameter::gen_CircularNormalUniform() { } } -void InitParameter::get_CircularNormalNormal(Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { +void InitParameter::get_CircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { // r and θ follow normal distribution in Circular frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = InitParameter::Normal_1d(theta_mean, theta_sigma); @@ -151,7 +151,7 @@ void InitParameter::gen_CircularNormalNormal() { if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; } - Vector temp_vec; + libra::Vector temp_vec; get_CircularNormalNormal(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); val_.clear(); @@ -160,8 +160,8 @@ void InitParameter::gen_CircularNormalNormal() { } } -void InitParameter::get_SphericalNormalUniformUniform(Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, - double phi_min, double phi_max) { +void InitParameter::get_SphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, + double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame double r = InitParameter::Normal_1d(r_mean, r_sigma); double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitParameter::Uniform_1d(0.0, 1.0)); @@ -176,7 +176,7 @@ void InitParameter::gen_SphericalNormalUniformUniform() { if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; } - Vector temp_vec; + libra::Vector temp_vec; get_SphericalNormalUniformUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1], mean_or_min_[2], sigma_or_max_[2]); @@ -186,28 +186,29 @@ void InitParameter::gen_SphericalNormalUniformUniform() { } } -void InitParameter::get_SphericalNormalNormal(Vector<3>& destination, const Vector<3>& mean_vec) { +void InitParameter::get_SphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] - Vector<3> mean_vec_dir; + libra::Vector<3> mean_vec_dir; mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction - Vector<3> x_axis(0.0), y_axis(0.0); + libra::Vector<3> x_axis(0.0), y_axis(0.0); x_axis[0] = 1.0; y_axis[1] = 1.0; - Vector<3> op_x = OuterProduct(mean_vec_dir, x_axis); - Vector<3> op_y = OuterProduct(mean_vec_dir, y_axis); + libra::Vector<3> op_x = OuterProduct(mean_vec_dir, x_axis); + libra::Vector<3> op_y = OuterProduct(mean_vec_dir, y_axis); // An unit vector perpendicular with the mean vector // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product - Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); + libra::Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); double rotation_angle_of_normal_unit_vec = InitParameter::Uniform_1d(0.0, libra::tau); - Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) - Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation + libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, + -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) + libra::Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation double rotation_angle_of_mean_vec = InitParameter::Normal_1d(0.0, sigma_or_max_[1]); - Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) - Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction + libra::Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) + libra::Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction ret_vec = InitParameter::Normal_1d(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm @@ -221,7 +222,7 @@ void InitParameter::gen_SphericalNormalNormal() { if (mean_or_min_.size() < dim || sigma_or_max_.size() < 2) { throw "Config parameters dimension unmatched."; } - Vector temp_vec, temp_mean_vec; + libra::Vector temp_vec, temp_mean_vec; for (int i = 0; i < dim; i++) { temp_mean_vec[i] = mean_or_min_[i]; } @@ -233,14 +234,14 @@ void InitParameter::gen_SphericalNormalNormal() { } } -void InitParameter::get_QuaternionUniform(Quaternion& destination) { - // Perfectly Randomized Quaternion - Vector<3> x_axis(0.0); +void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { + // Perfectly Randomized libra::Quaternion + libra::Vector<3> x_axis(0.0); x_axis[0] = 1.0; // A direction vector converted from the X-axis by a quaternion may follows the uniform distribution in full sphere. - Quaternion first_cnv; - Vector<3> x_axis_cnvd; + libra::Quaternion first_cnv; + libra::Vector<3> x_axis_cnvd; double theta = acos(1 - (1 - (-1)) * InitParameter::Uniform_1d(0.0, 1.0)); double phi = InitParameter::Uniform_1d(0, libra::tau); x_axis_cnvd[0] = sin(theta) * cos(phi); @@ -248,7 +249,7 @@ void InitParameter::get_QuaternionUniform(Quaternion& destination) { x_axis_cnvd[2] = cos(theta); double cos_angle_between = InnerProduct(x_axis, x_axis_cnvd); - Vector<3> op = OuterProduct(x_axis, x_axis_cnvd); + libra::Vector<3> op = OuterProduct(x_axis, x_axis_cnvd); for (int i = 0; i < 3; i++) { first_cnv[i] = op[i]; } @@ -256,9 +257,9 @@ void InitParameter::get_QuaternionUniform(Quaternion& destination) { // Generate randomized rotation angle around the X-axis double rotation_angle = InitParameter::Uniform_1d(0.0, libra::tau); - Quaternion second_cnv(x_axis, rotation_angle); + libra::Quaternion second_cnv(x_axis, rotation_angle); - Quaternion ret_q = first_cnv * second_cnv; + libra::Quaternion ret_q = first_cnv * second_cnv; for (int i = 0; i < 4; i++) { destination[i] = ret_q[i]; @@ -267,7 +268,7 @@ void InitParameter::get_QuaternionUniform(Quaternion& destination) { void InitParameter::gen_QuaternionUniform() { const static int dim = 4; - Quaternion temp_q; + libra::Quaternion temp_q; get_QuaternionUniform(temp_q); val_.clear(); @@ -276,10 +277,10 @@ void InitParameter::gen_QuaternionUniform() { } } -void InitParameter::get_QuaternionNormal(Quaternion& destination, double theta_sigma) { +void InitParameter::get_QuaternionNormal(libra::Quaternion& destination, double theta_sigma) { // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere - Vector<3> rot_axis; + libra::Vector<3> rot_axis; double theta = acos(1 - (1 - (-1)) * InitParameter::Uniform_1d(0.0, 1.0)); double phi = InitParameter::Uniform_1d(0, libra::tau); rot_axis[0] = sin(theta) * cos(phi); @@ -288,7 +289,7 @@ void InitParameter::get_QuaternionNormal(Quaternion& destination, double theta_s double rotation_angle = InitParameter::Normal_1d(0.0, theta_sigma); - Quaternion ret_q(rot_axis, rotation_angle); + libra::Quaternion ret_q(rot_axis, rotation_angle); for (int i = 0; i < 4; i++) { destination[i] = ret_q[i]; } @@ -300,7 +301,7 @@ void InitParameter::gen_QuaternionNormal() { if (sigma_or_max_.size() < 1) { throw "Config parameters dimension unmatched."; } - Quaternion temp_q; + libra::Quaternion temp_q; get_QuaternionNormal(temp_q, sigma_or_max_[0]); val_.clear(); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index f539b7e2b..bcf4f19c2 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -13,9 +13,6 @@ #include #include -using libra::Quaternion; -using libra::Vector; - /** * @class InitParameter * @brief Initialized parameters for Monte-Carlo simulation @@ -34,7 +31,7 @@ class InitParameter { CircularNormalNormal, //!< r and θ follow normal distribution in Circular frame SphericalNormalUniformUniform, //!< r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame SphericalNormalNormal, //!< r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] - QuaternionUniform, //!< Perfectly Randomized Quaternion + QuaternionUniform, //!< Perfectly Randomized libra::Quaternion QuaternionNormal, //!< Angle from the default quaternion θ follows normal distribution }; @@ -55,7 +52,7 @@ class InitParameter { * @brief Set randomization parameters */ template - void SetRandomConfig(const Vector& mean_or_min, const Vector& sigma_or_max, RandomizationType rnd_type); + void SetRandomConfig(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, RandomizationType rnd_type); // Getter /** @@ -63,12 +60,12 @@ class InitParameter { * @brief Get randomized vector value results */ template - void GetVec(Vector& destination) const; + void GetVec(libra::Vector& destination) const; /** * @fn GetQuaternion * @brief Get randomized quaternion results */ - void GetQuaternion(Quaternion& destination) const; + void GetQuaternion(libra::Quaternion& destination) const; /** * @fn GetDouble * @brief Get randomized value results @@ -177,37 +174,37 @@ class InitParameter { * @fn get_CircularNormalUniform * @brief Calculate randomized value with CircularNormalUniform mode */ - void get_CircularNormalUniform(Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max); + void get_CircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max); /** * @fn get_CircularNormalNormal * @brief Calculate randomized value with CircularNormalNormal mode */ - void get_CircularNormalNormal(Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma); + void get_CircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma); /** * @fn get_SphericalNormalUniformUniform * @brief Calculate randomized value with SphericalNormalUniformUniform mode */ - void get_SphericalNormalUniformUniform(Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, - double phi_max); + void get_SphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, + double phi_min, double phi_max); /** * @fn get_SphericalNormalNormal * @brief Calculate randomized value with SphericalNormalNormal mode */ - void get_SphericalNormalNormal(Vector<3>& destination, const Vector<3>& mean_vec); + void get_SphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec); /** * @fn get_QuaternionUniform * @brief Calculate randomized value with QuaternionUniform mode */ - void get_QuaternionUniform(Quaternion& destination); + void get_QuaternionUniform(libra::Quaternion& destination); /** * @fn get_QuaternionNormal * @brief Calculate randomized value with QuaternionNormal mode */ - void get_QuaternionNormal(Quaternion& destination, double theta_sigma); + void get_QuaternionNormal(libra::Quaternion& destination, double theta_sigma); }; template -void InitParameter::SetRandomConfig(const Vector& mean_or_min, const Vector& sigma_or_max, +void InitParameter::SetRandomConfig(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type) { rnd_type_ = rnd_type; mean_or_min_.clear(); @@ -221,7 +218,7 @@ void InitParameter::SetRandomConfig(const Vector& mean_or_min, cons } template -void InitParameter::GetVec(Vector& destination) const { +void InitParameter::GetVec(libra::Vector& destination) const { if (rnd_type_ == NoRandomization) { ; } else if (NumElement > val_.size()) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 1c5772ee3..057fe9374 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -79,12 +79,12 @@ MCSimExecutor* InitMCSim(std::string file_name) { // Read mean_or_min vector key_name = so_dot_ip_str + MCSimExecutor::separator_ + "mean_or_min"; - Vector<3> mean_or_min; + libra::Vector<3> mean_or_min; ini_file.ReadVector(section, key_name.c_str(), mean_or_min); // Read sigma_or_max vector key_name = so_dot_ip_str + MCSimExecutor::separator_ + "sigma_or_max"; - Vector<3> sigma_or_max; + libra::Vector<3> sigma_or_max; ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); // Write randomize setting diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 03f3fb868..53484869c 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -44,7 +44,7 @@ void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, doubl } } -void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, Quaternion& destination) const { +void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { if (!enabled_) return; { string name = so_name + MCSimExecutor::separator_ + ip_name; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index e9f315810..9e66efeb9 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -12,8 +12,6 @@ // #include "simulation_object.hpp" #include "initialize_monte_carlo_parameters.hpp" -using libra::Vector; - /** * @class MCSimExecutor * @brief Monte-Carlo Simulation Executor class @@ -84,7 +82,7 @@ class MCSimExecutor { * @brief Get randomized vector value and store it in dest_vec */ template - void GetInitParameterVec(std::string so_name, std::string ip_name, Vector& destination) const; + void GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const; /** * @fn GetInitParameterDouble * @brief Get randomized value and store it in dest @@ -94,7 +92,7 @@ class MCSimExecutor { * @fn GetInitParameterQuaternion * @brief Get randomized quaternion and store it in dest_quat */ - void GetInitParameterQuaternion(std::string so_name, std::string ip_name, Quaternion& destination) const; + void GetInitParameterQuaternion(std::string so_name, std::string ip_name, libra::Quaternion& destination) const; // Calculation /** @@ -122,8 +120,8 @@ class MCSimExecutor { * @fn AddInitParameter * @brief Add initialized parameter */ - void AddInitParameter(std::string so_name, std::string ip_name, const Vector& mean_or_min, const Vector& sigma_or_max, - InitParameter::RandomizationType rnd_type); + void AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type); /** * @fn RandomizeAllParameters @@ -150,7 +148,7 @@ bool MCSimExecutor::LogHistory() const { void MCSimExecutor::LogHistory(bool set) { log_history_ = set; } template -void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, Vector& destination) const { +void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const { if (!enabled_) return; std::string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { @@ -162,8 +160,8 @@ void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name } template -void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const Vector& mean_or_min, - const Vector& sigma_or_max, InitParameter::RandomizationType rnd_type) { +void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type) { std::string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Register the parameter in ip_list if it is not registered yet diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index 33e4f1ea7..bc62533e2 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -111,11 +111,11 @@ void RelativeInformation::LogSetup(Logger& logger) { logger.AddLogList(this); } libra::Quaternion RelativeInformation::CalcRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id) { // Observer SC Body frame(obs_sat) -> ECI frame(i) - Quaternion q_reference_i2b = dynamics_database_.at(reference_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); - Quaternion q_reference_b2i = q_reference_i2b.Conjugate(); + libra::Quaternion q_reference_i2b = dynamics_database_.at(reference_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); + libra::Quaternion q_reference_b2i = q_reference_i2b.Conjugate(); // ECI frame(i) -> Target SC body frame(main_sat) - Quaternion q_target_i2b = dynamics_database_.at(target_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); + libra::Quaternion q_target_i2b = dynamics_database_.at(target_spacecraft_id)->GetAttitude().GetQuaternion_i2b(); return q_target_i2b * q_reference_b2i; } From b655cae3354521405c566352cd02e1a5b05cb801 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 15:56:48 +0100 Subject: [PATCH 0910/1086] Fix private variables name --- .../initialize_monte_carlo_parameters.cpp | 66 +++++++++---------- .../initialize_monte_carlo_parameters.hpp | 20 +++--- 2 files changed, 43 insertions(+), 43 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 62768f6ae..380fafc9c 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -9,51 +9,51 @@ using namespace std; -random_device InitParameter::rnd_; +random_device InitParameter::randomizer_; mt19937 InitParameter::mt_; -uniform_real_distribution<>* InitParameter::uniform_dist_; -normal_distribution<>* InitParameter::normal_dist_; +uniform_real_distribution<>* InitParameter::uniform_distribution_; +normal_distribution<>* InitParameter::normal_distribution_; InitParameter::InitParameter() { // Generate object when the first execution static bool initial_setup_done = false; if (!initial_setup_done) { SetSeed(); - InitParameter::uniform_dist_ = new uniform_real_distribution<>(0.0, 1.0); - InitParameter::normal_dist_ = new normal_distribution<>(0.0, 1.0); + InitParameter::uniform_distribution_ = new uniform_real_distribution<>(0.0, 1.0); + InitParameter::normal_distribution_ = new normal_distribution<>(0.0, 1.0); initial_setup_done = true; } // No randomization when SetRandomConfig is not called(No setting in MCSim.ini) - rnd_type_ = NoRandomization; + randomization_type_ = NoRandomization; } void InitParameter::SetSeed(unsigned long seed, bool is_deterministic) { if (is_deterministic) { InitParameter::mt_.seed(seed); } else { - InitParameter::mt_.seed(InitParameter::rnd_()); + InitParameter::mt_.seed(InitParameter::randomizer_()); } } void InitParameter::GetDouble(double& destination) const { - if (rnd_type_ == NoRandomization) { + if (randomization_type_ == NoRandomization) { ; - } else if (1 > val_.size()) { + } else if (1 > randomized_value_.size()) { throw "Too few randomization configuration parameters."; } else { - destination = val_[0]; + destination = randomized_value_[0]; } } void InitParameter::GetQuaternion(libra::Quaternion& destination) const { - if (rnd_type_ == NoRandomization) { + if (randomization_type_ == NoRandomization) { ; - } else if (4 > val_.size()) { + } else if (4 > randomized_value_.size()) { throw "Too few randomization configuration parameters."; } else { for (int i = 0; i < 4; i++) { - destination[i] = val_[i]; + destination[i] = randomized_value_[i]; } } @@ -61,7 +61,7 @@ void InitParameter::GetQuaternion(libra::Quaternion& destination) const { } void InitParameter::Randomize() { - switch (rnd_type_) { + switch (randomization_type_) { case NoRandomization: gen_NoRandomization(); break; @@ -94,25 +94,25 @@ void InitParameter::Randomize() { } } -double InitParameter::Uniform_1d(double lb, double ub) { return lb + (*InitParameter::uniform_dist_)(InitParameter::mt_) * (ub - lb); } +double InitParameter::Uniform_1d(double lb, double ub) { return lb + (*InitParameter::uniform_distribution_)(InitParameter::mt_) * (ub - lb); } -double InitParameter::Normal_1d(double mean, double std) { return mean + (*InitParameter::normal_dist_)(InitParameter::mt_) * (std); } +double InitParameter::Normal_1d(double mean, double std) { return mean + (*InitParameter::normal_distribution_)(InitParameter::mt_) * (std); } -void InitParameter::gen_NoRandomization() { val_.clear(); } +void InitParameter::gen_NoRandomization() { randomized_value_.clear(); } void InitParameter::gen_CartesianUniform() { // Random variables following a uniform distribution in Cartesian frame - val_.clear(); + randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - val_.push_back(InitParameter::Uniform_1d(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitParameter::Uniform_1d(mean_or_min_[i], sigma_or_max_[i])); } } void InitParameter::gen_CartesianNormal() { // Random variables following a normal distribution in Cartesian frame - val_.clear(); + randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - val_.push_back(InitParameter::Normal_1d(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitParameter::Normal_1d(mean_or_min_[i], sigma_or_max_[i])); } } @@ -132,9 +132,9 @@ void InitParameter::gen_CircularNormalUniform() { libra::Vector temp_vec; get_CircularNormalUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_vec[i]); + randomized_value_.push_back(temp_vec[i]); } } @@ -154,9 +154,9 @@ void InitParameter::gen_CircularNormalNormal() { libra::Vector temp_vec; get_CircularNormalNormal(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_vec[i]); + randomized_value_.push_back(temp_vec[i]); } } @@ -180,9 +180,9 @@ void InitParameter::gen_SphericalNormalUniformUniform() { get_SphericalNormalUniformUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1], mean_or_min_[2], sigma_or_max_[2]); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_vec[i]); + randomized_value_.push_back(temp_vec[i]); } } @@ -228,9 +228,9 @@ void InitParameter::gen_SphericalNormalNormal() { } get_SphericalNormalNormal(temp_vec, temp_mean_vec); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_vec[i]); + randomized_value_.push_back(temp_vec[i]); } } @@ -271,9 +271,9 @@ void InitParameter::gen_QuaternionUniform() { libra::Quaternion temp_q; get_QuaternionUniform(temp_q); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_q[i]); + randomized_value_.push_back(temp_q[i]); } } @@ -304,8 +304,8 @@ void InitParameter::gen_QuaternionNormal() { libra::Quaternion temp_q; get_QuaternionNormal(temp_q, sigma_or_max_[0]); - val_.clear(); + randomized_value_.clear(); for (int i = 0; i < dim; i++) { - val_.push_back(temp_q[i]); + randomized_value_.push_back(temp_q[i]); } } diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index bcf4f19c2..60ea9f8d5 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -80,17 +80,17 @@ class InitParameter { void Randomize(); private: - std::vector val_; //!< Randomized value + std::vector randomized_value_; //!< Randomized value std::vector mean_or_min_; //!< mean or minimum value. Refer comment in gen_[RandomizationType] function. std::vector sigma_or_max_; //!< standard deviation or maximum value. Refer comment in gen_[RandomizationType] function. // For randomization - RandomizationType rnd_type_; //!< Randomization type - static std::random_device rnd_; //!< Non-deterministic random number generator with time information - static std::mt19937 mt_; //!< Deterministic random number generator - static std::uniform_real_distribution<>* uniform_dist_; //!< Uniform random number generator - static std::normal_distribution<>* normal_dist_; //!< Normal random number generator + RandomizationType randomization_type_; //!< Randomization type + static std::random_device randomizer_; //!< Non-deterministic random number generator with time information + static std::mt19937 mt_; //!< Deterministic random number generator + static std::uniform_real_distribution<>* uniform_distribution_; //!< Uniform random number generator + static std::normal_distribution<>* normal_distribution_; //!< Normal random number generator /** * @fn Uniform_1d @@ -206,7 +206,7 @@ class InitParameter { template void InitParameter::SetRandomConfig(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type) { - rnd_type_ = rnd_type; + randomization_type_ = rnd_type; mean_or_min_.clear(); for (size_t i = 0; i < NumElement1; i++) { mean_or_min_.push_back(mean_or_min[i]); @@ -219,13 +219,13 @@ void InitParameter::SetRandomConfig(const libra::Vector& mean_or_mi template void InitParameter::GetVec(libra::Vector& destination) const { - if (rnd_type_ == NoRandomization) { + if (randomization_type_ == NoRandomization) { ; - } else if (NumElement > val_.size()) { + } else if (NumElement > randomized_value_.size()) { throw "Too few randomization configuration parameters."; } else { for (size_t i = 0; i < NumElement; i++) { - destination[i] = val_[i]; + destination[i] = randomized_value_[i]; } } } From 8785c12cd4c3e27cbd8407cf399ec3dbcc32119f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:02:14 +0100 Subject: [PATCH 0911/1086] Fix private function name --- .../initialize_monte_carlo_parameters.cpp | 76 +++++++++---------- .../initialize_monte_carlo_parameters.hpp | 48 ++++++------ 2 files changed, 62 insertions(+), 62 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 380fafc9c..b9a557a4e 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -63,68 +63,68 @@ void InitParameter::GetQuaternion(libra::Quaternion& destination) const { void InitParameter::Randomize() { switch (randomization_type_) { case NoRandomization: - gen_NoRandomization(); + GenerateNoRandomization(); break; case CartesianUniform: - gen_CartesianUniform(); + GenerateCartesianUniform(); break; case CartesianNormal: - gen_CartesianNormal(); + GenerateCartesianNormal(); break; case CircularNormalUniform: - gen_CircularNormalUniform(); + GenerateCircularNormalUniform(); break; case CircularNormalNormal: - gen_CircularNormalNormal(); + GenerateCircularNormalNormal(); break; case SphericalNormalUniformUniform: - gen_SphericalNormalUniformUniform(); + GenerateSphericalNormalUniformUniform(); break; case SphericalNormalNormal: - gen_SphericalNormalNormal(); + GenerateSphericalNormalNormal(); break; case QuaternionUniform: - gen_QuaternionUniform(); + GenerateQuaternionUniform(); break; case QuaternionNormal: - gen_QuaternionNormal(); + GenerateQuaternionNormal(); break; default: break; } } -double InitParameter::Uniform_1d(double lb, double ub) { return lb + (*InitParameter::uniform_distribution_)(InitParameter::mt_) * (ub - lb); } +double InitParameter::Generate1dUniform(double lb, double ub) { return lb + (*InitParameter::uniform_distribution_)(InitParameter::mt_) * (ub - lb); } -double InitParameter::Normal_1d(double mean, double std) { return mean + (*InitParameter::normal_distribution_)(InitParameter::mt_) * (std); } +double InitParameter::Generate1dNormal(double mean, double std) { return mean + (*InitParameter::normal_distribution_)(InitParameter::mt_) * (std); } -void InitParameter::gen_NoRandomization() { randomized_value_.clear(); } +void InitParameter::GenerateNoRandomization() { randomized_value_.clear(); } -void InitParameter::gen_CartesianUniform() { +void InitParameter::GenerateCartesianUniform() { // Random variables following a uniform distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitParameter::Uniform_1d(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitParameter::Generate1dUniform(mean_or_min_[i], sigma_or_max_[i])); } } -void InitParameter::gen_CartesianNormal() { +void InitParameter::GenerateCartesianNormal() { // Random variables following a normal distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitParameter::Normal_1d(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitParameter::Generate1dNormal(mean_or_min_[i], sigma_or_max_[i])); } } void InitParameter::get_CircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame - double r = InitParameter::Normal_1d(r_mean, r_sigma); - double theta = InitParameter::Uniform_1d(theta_min, theta_max); + double r = InitParameter::Generate1dNormal(r_mean, r_sigma); + double theta = InitParameter::Generate1dUniform(theta_min, theta_max); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitParameter::gen_CircularNormalUniform() { +void InitParameter::GenerateCircularNormalUniform() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -140,13 +140,13 @@ void InitParameter::gen_CircularNormalUniform() { void InitParameter::get_CircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { // r and θ follow normal distribution in Circular frame - double r = InitParameter::Normal_1d(r_mean, r_sigma); - double theta = InitParameter::Normal_1d(theta_mean, theta_sigma); + double r = InitParameter::Generate1dNormal(r_mean, r_sigma); + double theta = InitParameter::Generate1dNormal(theta_mean, theta_sigma); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitParameter::gen_CircularNormalNormal() { +void InitParameter::GenerateCircularNormalNormal() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -163,15 +163,15 @@ void InitParameter::gen_CircularNormalNormal() { void InitParameter::get_SphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame - double r = InitParameter::Normal_1d(r_mean, r_sigma); - double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitParameter::Uniform_1d(0.0, 1.0)); - double phi = InitParameter::Uniform_1d(phi_min, phi_max); + double r = InitParameter::Generate1dNormal(r_mean, r_sigma); + double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitParameter::Generate1dUniform(0.0, 1.0)); + double phi = InitParameter::Generate1dUniform(phi_min, phi_max); destination[0] = r * sin(theta) * cos(phi); destination[1] = r * sin(theta) * sin(phi); destination[2] = r * cos(theta); } -void InitParameter::gen_SphericalNormalUniformUniform() { +void InitParameter::GenerateSphericalNormalUniformUniform() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -201,23 +201,23 @@ void InitParameter::get_SphericalNormalNormal(libra::Vector<3>& destination, con // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product libra::Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); - double rotation_angle_of_normal_unit_vec = InitParameter::Uniform_1d(0.0, libra::tau); + double rotation_angle_of_normal_unit_vec = InitParameter::Generate1dUniform(0.0, libra::tau); libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation - double rotation_angle_of_mean_vec = InitParameter::Normal_1d(0.0, sigma_or_max_[1]); + double rotation_angle_of_mean_vec = InitParameter::Generate1dNormal(0.0, sigma_or_max_[1]); libra::Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction - ret_vec = InitParameter::Normal_1d(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm + ret_vec = InitParameter::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { destination[i] = ret_vec[i]; } } -void InitParameter::gen_SphericalNormalNormal() { +void InitParameter::GenerateSphericalNormalNormal() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < 2) { throw "Config parameters dimension unmatched."; @@ -242,8 +242,8 @@ void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { // A direction vector converted from the X-axis by a quaternion may follows the uniform distribution in full sphere. libra::Quaternion first_cnv; libra::Vector<3> x_axis_cnvd; - double theta = acos(1 - (1 - (-1)) * InitParameter::Uniform_1d(0.0, 1.0)); - double phi = InitParameter::Uniform_1d(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitParameter::Generate1dUniform(0.0, 1.0)); + double phi = InitParameter::Generate1dUniform(0, libra::tau); x_axis_cnvd[0] = sin(theta) * cos(phi); x_axis_cnvd[1] = sin(theta) * sin(phi); x_axis_cnvd[2] = cos(theta); @@ -256,7 +256,7 @@ void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { first_cnv[3] = cos_angle_between; // Generate randomized rotation angle around the X-axis - double rotation_angle = InitParameter::Uniform_1d(0.0, libra::tau); + double rotation_angle = InitParameter::Generate1dUniform(0.0, libra::tau); libra::Quaternion second_cnv(x_axis, rotation_angle); libra::Quaternion ret_q = first_cnv * second_cnv; @@ -266,7 +266,7 @@ void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { } } -void InitParameter::gen_QuaternionUniform() { +void InitParameter::GenerateQuaternionUniform() { const static int dim = 4; libra::Quaternion temp_q; get_QuaternionUniform(temp_q); @@ -281,13 +281,13 @@ void InitParameter::get_QuaternionNormal(libra::Quaternion& destination, double // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere libra::Vector<3> rot_axis; - double theta = acos(1 - (1 - (-1)) * InitParameter::Uniform_1d(0.0, 1.0)); - double phi = InitParameter::Uniform_1d(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitParameter::Generate1dUniform(0.0, 1.0)); + double phi = InitParameter::Generate1dUniform(0, libra::tau); rot_axis[0] = sin(theta) * cos(phi); rot_axis[1] = sin(theta) * sin(phi); rot_axis[2] = cos(theta); - double rotation_angle = InitParameter::Normal_1d(0.0, theta_sigma); + double rotation_angle = InitParameter::Generate1dNormal(0.0, theta_sigma); libra::Quaternion ret_q(rot_axis, rotation_angle); for (int i = 0; i < 4; i++) { @@ -295,7 +295,7 @@ void InitParameter::get_QuaternionNormal(libra::Quaternion& destination, double } } -void InitParameter::gen_QuaternionNormal() { +void InitParameter::GenerateQuaternionNormal() { // mean_or_min_[0]: NA sigma_or_max_[0]: standard deviation of θ [rad] const static int dim = 4; if (sigma_or_max_.size() < 1) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 60ea9f8d5..948af20a6 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -82,8 +82,8 @@ class InitParameter { private: std::vector randomized_value_; //!< Randomized value - std::vector mean_or_min_; //!< mean or minimum value. Refer comment in gen_[RandomizationType] function. - std::vector sigma_or_max_; //!< standard deviation or maximum value. Refer comment in gen_[RandomizationType] function. + std::vector mean_or_min_; //!< mean or minimum value. Refer comment in Generate[RandomizationType] function. + std::vector sigma_or_max_; //!< standard deviation or maximum value. Refer comment in Generate[RandomizationType] function. // For randomization RandomizationType randomization_type_; //!< Randomization type @@ -93,81 +93,81 @@ class InitParameter { static std::normal_distribution<>* normal_distribution_; //!< Normal random number generator /** - * @fn Uniform_1d + * @fn Generate1dUniform * @brief Generate 1-dimensional uniform distribution random number */ - static double Uniform_1d(double lb, double ub); + static double Generate1dUniform(double lb, double ub); /** - * @fn Normal_1d + * @fn Generate1dNormal * @brief Generate 1-dimensional normal distribution random number */ - static double Normal_1d(double mean, double std); + static double Generate1dNormal(double mean, double std); // Generate randomized value /** - * @fn gen_NoRandomization + * @fn GenerateNoRandomization * @brief Generate randomized value with NoRandomization mode */ - void gen_NoRandomization(); + void GenerateNoRandomization(); /** - * @fn gen_CartesianUniform + * @fn GenerateCartesianUniform * @brief Generate randomized value with CartesianUniform mode * @note Support up to three dimensional value * @note mean_or_min_[0]: minimum of x sigma_or_max_[0]: maximum of x * mean_or_min_[1]: minimum of y sigma_or_max_[1]: maximum of y * mean_or_min_[2]: minimum of z sigma_or_max_[2]: maximum of z */ - void gen_CartesianUniform(); + void GenerateCartesianUniform(); /** - * @fn gen_CartesianNormal + * @fn GenerateCartesianNormal * @brief Generate randomized value with CartesianNormal mode * @note Support up to three dimensional value * @note mean_or_min_[0]: average of x sigma_or_max_[0]: sigma of x * mean_or_min_[1]: average of y sigma_or_max_[1]: sigma of y * mean_or_min_[2]: average of z sigma_or_max_[2]: sigma of z */ - void gen_CartesianNormal(); + void GenerateCartesianNormal(); /** - * @fn gen_CircularNormalUniform + * @fn GenerateCircularNormalUniform * @brief Generate randomized value with CircularNormalUniform mode * @note mean_or_min_[0]: average of r sigma_or_max_[0]: sigma of r * mean_or_min_[1]: minimum of θ sigma_or_max_[1]: maximum of θ */ - void gen_CircularNormalUniform(); + void GenerateCircularNormalUniform(); /** - * @fn gen_CircularNormalNormal + * @fn GenerateCircularNormalNormal * @brief Generate randomized value with CircularNormalNormal mode * @details mean_or_min_[0]: average of r sigma_or_max_[0]: sigma of r * @details mean_or_min_[1]: average of θ sigma_or_max_[1]: sigma of θ */ - void gen_CircularNormalNormal(); + void GenerateCircularNormalNormal(); /** - * @fn gen_SphericalNormalUniformUniform + * @fn GenerateSphericalNormalUniformUniform * @brief Generate randomized value with SphericalNormalUniformUniform mode * @note mean_or_min_[0]: average of r sigma_or_max_[0]: sigma of r * mean_or_min_[1]: minimum of θ sigma_or_max_[1]: maximum of θ * mean_or_min_[2]: minimum of φ sigma_or_max_[2]: maximum of φ */ - void gen_SphericalNormalUniformUniform(); + void GenerateSphericalNormalUniformUniform(); /** - * @fn gen_SphericalNormalNormal + * @fn GenerateSphericalNormalNormal * @brief Generate randomized value with SphericalNormalNormal mode * @note mean_or_min_[0]: average of X sigma_or_max_[0]: sigma of r * mean_or_min_[1]: average of Y sigma_or_max_[1]: sigma of θ * mean_or_min_[2]: average of Z sigma_or_max_[2]: なし */ - void gen_SphericalNormalNormal(); + void GenerateSphericalNormalNormal(); /** - * @fn gen_QuaternionUniform + * @fn GenerateQuaternionUniform * @brief Generate randomized value with QuaternionUniform mode */ - void gen_QuaternionUniform(); + void GenerateQuaternionUniform(); /** - * @fn gen_QuaternionNormal + * @fn GenerateQuaternionNormal * @brief Generate randomized value with QuaternionNormal mode * @note mean_or_min_[0]: NA sigma_or_max_[0]: standard deviation of θ [rad] */ - void gen_QuaternionNormal(); + void GenerateQuaternionNormal(); // Get randomized value /** From eaf39922bb8cc843a023e09f22436469e8c5421b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:03:14 +0100 Subject: [PATCH 0912/1086] Fix private function name --- .../initialize_monte_carlo_parameters.cpp | 24 +++++++++---------- .../initialize_monte_carlo_parameters.hpp | 24 +++++++++---------- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index b9a557a4e..947142ba0 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -116,7 +116,7 @@ void InitParameter::GenerateCartesianNormal() { } } -void InitParameter::get_CircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { +void InitParameter::CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame double r = InitParameter::Generate1dNormal(r_mean, r_sigma); double theta = InitParameter::Generate1dUniform(theta_min, theta_max); @@ -130,7 +130,7 @@ void InitParameter::GenerateCircularNormalUniform() { throw "Config parameters dimension unmatched."; } libra::Vector temp_vec; - get_CircularNormalUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); + CalcCircularNormalUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); randomized_value_.clear(); for (int i = 0; i < dim; i++) { @@ -138,7 +138,7 @@ void InitParameter::GenerateCircularNormalUniform() { } } -void InitParameter::get_CircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { +void InitParameter::CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { // r and θ follow normal distribution in Circular frame double r = InitParameter::Generate1dNormal(r_mean, r_sigma); double theta = InitParameter::Generate1dNormal(theta_mean, theta_sigma); @@ -152,7 +152,7 @@ void InitParameter::GenerateCircularNormalNormal() { throw "Config parameters dimension unmatched."; } libra::Vector temp_vec; - get_CircularNormalNormal(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); + CalcCircularNormalNormal(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1]); randomized_value_.clear(); for (int i = 0; i < dim; i++) { @@ -160,7 +160,7 @@ void InitParameter::GenerateCircularNormalNormal() { } } -void InitParameter::get_SphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, +void InitParameter::CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame double r = InitParameter::Generate1dNormal(r_mean, r_sigma); @@ -177,7 +177,7 @@ void InitParameter::GenerateSphericalNormalUniformUniform() { throw "Config parameters dimension unmatched."; } libra::Vector temp_vec; - get_SphericalNormalUniformUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1], mean_or_min_[2], + CalcSphericalNormalUniformUniform(temp_vec, mean_or_min_[0], sigma_or_max_[0], mean_or_min_[1], sigma_or_max_[1], mean_or_min_[2], sigma_or_max_[2]); randomized_value_.clear(); @@ -186,7 +186,7 @@ void InitParameter::GenerateSphericalNormalUniformUniform() { } } -void InitParameter::get_SphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { +void InitParameter::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] libra::Vector<3> mean_vec_dir; mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction @@ -226,7 +226,7 @@ void InitParameter::GenerateSphericalNormalNormal() { for (int i = 0; i < dim; i++) { temp_mean_vec[i] = mean_or_min_[i]; } - get_SphericalNormalNormal(temp_vec, temp_mean_vec); + CalcSphericalNormalNormal(temp_vec, temp_mean_vec); randomized_value_.clear(); for (int i = 0; i < dim; i++) { @@ -234,7 +234,7 @@ void InitParameter::GenerateSphericalNormalNormal() { } } -void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { +void InitParameter::CalcQuaternionUniform(libra::Quaternion& destination) { // Perfectly Randomized libra::Quaternion libra::Vector<3> x_axis(0.0); x_axis[0] = 1.0; @@ -269,7 +269,7 @@ void InitParameter::get_QuaternionUniform(libra::Quaternion& destination) { void InitParameter::GenerateQuaternionUniform() { const static int dim = 4; libra::Quaternion temp_q; - get_QuaternionUniform(temp_q); + CalcQuaternionUniform(temp_q); randomized_value_.clear(); for (int i = 0; i < dim; i++) { @@ -277,7 +277,7 @@ void InitParameter::GenerateQuaternionUniform() { } } -void InitParameter::get_QuaternionNormal(libra::Quaternion& destination, double theta_sigma) { +void InitParameter::CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma) { // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere libra::Vector<3> rot_axis; @@ -302,7 +302,7 @@ void InitParameter::GenerateQuaternionNormal() { throw "Config parameters dimension unmatched."; } libra::Quaternion temp_q; - get_QuaternionNormal(temp_q, sigma_or_max_[0]); + CalcQuaternionNormal(temp_q, sigma_or_max_[0]); randomized_value_.clear(); for (int i = 0; i < dim; i++) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 948af20a6..515d55f7b 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -171,36 +171,36 @@ class InitParameter { // Get randomized value /** - * @fn get_CircularNormalUniform + * @fn CalcCircularNormalUniform * @brief Calculate randomized value with CircularNormalUniform mode */ - void get_CircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max); + void CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max); /** - * @fn get_CircularNormalNormal + * @fn CalcCircularNormalNormal * @brief Calculate randomized value with CircularNormalNormal mode */ - void get_CircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma); + void CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma); /** - * @fn get_SphericalNormalUniformUniform + * @fn CalcSphericalNormalUniformUniform * @brief Calculate randomized value with SphericalNormalUniformUniform mode */ - void get_SphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, + void CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, double theta_max, double phi_min, double phi_max); /** - * @fn get_SphericalNormalNormal + * @fn CalcSphericalNormalNormal * @brief Calculate randomized value with SphericalNormalNormal mode */ - void get_SphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec); + void CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec); /** - * @fn get_QuaternionUniform + * @fn CalcQuaternionUniform * @brief Calculate randomized value with QuaternionUniform mode */ - void get_QuaternionUniform(libra::Quaternion& destination); + void CalcQuaternionUniform(libra::Quaternion& destination); /** - * @fn get_QuaternionNormal + * @fn CalcQuaternionNormal * @brief Calculate randomized value with QuaternionNormal mode */ - void get_QuaternionNormal(libra::Quaternion& destination, double theta_sigma); + void CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma); }; template From 11eff8a4ae3779b8a21e021296216493dedc4b47 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:05:27 +0100 Subject: [PATCH 0913/1086] Fix public function name --- .../initialize_monte_carlo_parameters.cpp | 6 ++--- .../initialize_monte_carlo_parameters.hpp | 23 ++++++++++--------- .../monte_carlo_simulation_executor.cpp | 4 ++-- .../monte_carlo_simulation_executor.hpp | 4 ++-- 4 files changed, 19 insertions(+), 18 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 947142ba0..bb0538d23 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -24,7 +24,7 @@ InitParameter::InitParameter() { initial_setup_done = true; } - // No randomization when SetRandomConfig is not called(No setting in MCSim.ini) + // No randomization when SetRandomConfiguration is not called(No setting in MCSim.ini) randomization_type_ = NoRandomization; } @@ -36,7 +36,7 @@ void InitParameter::SetSeed(unsigned long seed, bool is_deterministic) { } } -void InitParameter::GetDouble(double& destination) const { +void InitParameter::GetRandomizedScalar(double& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (1 > randomized_value_.size()) { @@ -46,7 +46,7 @@ void InitParameter::GetDouble(double& destination) const { } } -void InitParameter::GetQuaternion(libra::Quaternion& destination) const { +void InitParameter::GetRandomizedQuaternion(libra::Quaternion& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (4 > randomized_value_.size()) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 515d55f7b..fa3c94786 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -48,29 +48,30 @@ class InitParameter { */ static void SetSeed(unsigned long seed = 0, bool is_deterministic = false); /** - * @fn SetRandomConfig + * @fn SetRandomConfiguration * @brief Set randomization parameters */ template - void SetRandomConfig(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, RandomizationType rnd_type); + void SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, + RandomizationType rnd_type); // Getter /** - * @fn GetVec + * @fn GetRandomizedVector * @brief Get randomized vector value results */ template - void GetVec(libra::Vector& destination) const; + void GetRandomizedVector(libra::Vector& destination) const; /** - * @fn GetQuaternion + * @fn GetRandomizedQuaternion * @brief Get randomized quaternion results */ - void GetQuaternion(libra::Quaternion& destination) const; + void GetRandomizedQuaternion(libra::Quaternion& destination) const; /** - * @fn GetDouble + * @fn GetRandomizedScalar * @brief Get randomized value results */ - void GetDouble(double& destination) const; + void GetRandomizedScalar(double& destination) const; // Calculation /** @@ -204,8 +205,8 @@ class InitParameter { }; template -void InitParameter::SetRandomConfig(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, - InitParameter::RandomizationType rnd_type) { +void InitParameter::SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, + InitParameter::RandomizationType rnd_type) { randomization_type_ = rnd_type; mean_or_min_.clear(); for (size_t i = 0; i < NumElement1; i++) { @@ -218,7 +219,7 @@ void InitParameter::SetRandomConfig(const libra::Vector& mean_or_mi } template -void InitParameter::GetVec(libra::Vector& destination) const { +void InitParameter::GetRandomizedVector(libra::Vector& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (NumElement > randomized_value_.size()) { diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 53484869c..62efb3ed0 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -39,7 +39,7 @@ void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, doubl // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination } else { - ip_list_.at(name)->GetDouble(destination); // cannot use operator[] since it is const map + ip_list_.at(name)->GetRandomizedScalar(destination); // cannot use operator[] since it is const map } } } @@ -52,7 +52,7 @@ void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, l // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination } else { - ip_list_.at(name)->GetQuaternion(destination); // cannot use operator[] since it is const map + ip_list_.at(name)->GetRandomizedQuaternion(destination); // cannot use operator[] since it is const map } } } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 9e66efeb9..b40b3bc06 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -155,7 +155,7 @@ void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name // Not registered in ip_list(Not defined in MCSim.ini) return; // return without update the destination } else { - ip_list_.at(name)->GetVec(destination); // cannot use operator[] since it is const map + ip_list_.at(name)->GetRandomizedVector(destination); // cannot use operator[] since it is const map } } @@ -166,7 +166,7 @@ void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, c if (ip_list_.find(name) == ip_list_.end()) { // Register the parameter in ip_list if it is not registered yet auto newparam = new InitParameter(); - newparam->SetRandomConfig(mean_or_min, sigma_or_max, rnd_type); + newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, rnd_type); ip_list_[name] = newparam; } else { // Throw error if the parameter is already registered From a0b6e1784a27301e7115bf439cfea8721e841863 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:06:18 +0100 Subject: [PATCH 0914/1086] Fix class name --- .../initialize_monte_carlo_parameters.cpp | 104 +++++++++--------- .../initialize_monte_carlo_parameters.hpp | 14 +-- .../initialize_monte_carlo_simulation.cpp | 24 ++-- .../monte_carlo_simulation_executor.cpp | 2 +- .../monte_carlo_simulation_executor.hpp | 12 +- 5 files changed, 81 insertions(+), 75 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index bb0538d23..19195b6a6 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -9,18 +9,18 @@ using namespace std; -random_device InitParameter::randomizer_; -mt19937 InitParameter::mt_; -uniform_real_distribution<>* InitParameter::uniform_distribution_; -normal_distribution<>* InitParameter::normal_distribution_; +random_device InitMonteCarloParameters::randomizer_; +mt19937 InitMonteCarloParameters::mt_; +uniform_real_distribution<>* InitMonteCarloParameters::uniform_distribution_; +normal_distribution<>* InitMonteCarloParameters::normal_distribution_; -InitParameter::InitParameter() { +InitMonteCarloParameters::InitMonteCarloParameters() { // Generate object when the first execution static bool initial_setup_done = false; if (!initial_setup_done) { SetSeed(); - InitParameter::uniform_distribution_ = new uniform_real_distribution<>(0.0, 1.0); - InitParameter::normal_distribution_ = new normal_distribution<>(0.0, 1.0); + InitMonteCarloParameters::uniform_distribution_ = new uniform_real_distribution<>(0.0, 1.0); + InitMonteCarloParameters::normal_distribution_ = new normal_distribution<>(0.0, 1.0); initial_setup_done = true; } @@ -28,15 +28,15 @@ InitParameter::InitParameter() { randomization_type_ = NoRandomization; } -void InitParameter::SetSeed(unsigned long seed, bool is_deterministic) { +void InitMonteCarloParameters::SetSeed(unsigned long seed, bool is_deterministic) { if (is_deterministic) { - InitParameter::mt_.seed(seed); + InitMonteCarloParameters::mt_.seed(seed); } else { - InitParameter::mt_.seed(InitParameter::randomizer_()); + InitMonteCarloParameters::mt_.seed(InitMonteCarloParameters::randomizer_()); } } -void InitParameter::GetRandomizedScalar(double& destination) const { +void InitMonteCarloParameters::GetRandomizedScalar(double& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (1 > randomized_value_.size()) { @@ -46,7 +46,7 @@ void InitParameter::GetRandomizedScalar(double& destination) const { } } -void InitParameter::GetRandomizedQuaternion(libra::Quaternion& destination) const { +void InitMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (4 > randomized_value_.size()) { @@ -60,7 +60,7 @@ void InitParameter::GetRandomizedQuaternion(libra::Quaternion& destination) cons destination.Normalize(); } -void InitParameter::Randomize() { +void InitMonteCarloParameters::Randomize() { switch (randomization_type_) { case NoRandomization: GenerateNoRandomization(); @@ -94,37 +94,42 @@ void InitParameter::Randomize() { } } -double InitParameter::Generate1dUniform(double lb, double ub) { return lb + (*InitParameter::uniform_distribution_)(InitParameter::mt_) * (ub - lb); } +double InitMonteCarloParameters::Generate1dUniform(double lb, double ub) { + return lb + (*InitMonteCarloParameters::uniform_distribution_)(InitMonteCarloParameters::mt_) * (ub - lb); +} -double InitParameter::Generate1dNormal(double mean, double std) { return mean + (*InitParameter::normal_distribution_)(InitParameter::mt_) * (std); } +double InitMonteCarloParameters::Generate1dNormal(double mean, double std) { + return mean + (*InitMonteCarloParameters::normal_distribution_)(InitMonteCarloParameters::mt_) * (std); +} -void InitParameter::GenerateNoRandomization() { randomized_value_.clear(); } +void InitMonteCarloParameters::GenerateNoRandomization() { randomized_value_.clear(); } -void InitParameter::GenerateCartesianUniform() { +void InitMonteCarloParameters::GenerateCartesianUniform() { // Random variables following a uniform distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitParameter::Generate1dUniform(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitMonteCarloParameters::Generate1dUniform(mean_or_min_[i], sigma_or_max_[i])); } } -void InitParameter::GenerateCartesianNormal() { +void InitMonteCarloParameters::GenerateCartesianNormal() { // Random variables following a normal distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitParameter::Generate1dNormal(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitMonteCarloParameters::Generate1dNormal(mean_or_min_[i], sigma_or_max_[i])); } } -void InitParameter::CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, double theta_max) { +void InitMonteCarloParameters::CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, + double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame - double r = InitParameter::Generate1dNormal(r_mean, r_sigma); - double theta = InitParameter::Generate1dUniform(theta_min, theta_max); + double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = InitMonteCarloParameters::Generate1dUniform(theta_min, theta_max); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitParameter::GenerateCircularNormalUniform() { +void InitMonteCarloParameters::GenerateCircularNormalUniform() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -138,15 +143,16 @@ void InitParameter::GenerateCircularNormalUniform() { } } -void InitParameter::CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, double theta_sigma) { +void InitMonteCarloParameters::CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, + double theta_sigma) { // r and θ follow normal distribution in Circular frame - double r = InitParameter::Generate1dNormal(r_mean, r_sigma); - double theta = InitParameter::Generate1dNormal(theta_mean, theta_sigma); + double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = InitMonteCarloParameters::Generate1dNormal(theta_mean, theta_sigma); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitParameter::GenerateCircularNormalNormal() { +void InitMonteCarloParameters::GenerateCircularNormalNormal() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -160,18 +166,18 @@ void InitParameter::GenerateCircularNormalNormal() { } } -void InitParameter::CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, - double theta_max, double phi_min, double phi_max) { +void InitMonteCarloParameters::CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, + double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame - double r = InitParameter::Generate1dNormal(r_mean, r_sigma); - double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitParameter::Generate1dUniform(0.0, 1.0)); - double phi = InitParameter::Generate1dUniform(phi_min, phi_max); + double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitMonteCarloParameters::Generate1dUniform(phi_min, phi_max); destination[0] = r * sin(theta) * cos(phi); destination[1] = r * sin(theta) * sin(phi); destination[2] = r * cos(theta); } -void InitParameter::GenerateSphericalNormalUniformUniform() { +void InitMonteCarloParameters::GenerateSphericalNormalUniformUniform() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -186,7 +192,7 @@ void InitParameter::GenerateSphericalNormalUniformUniform() { } } -void InitParameter::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { +void InitMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] libra::Vector<3> mean_vec_dir; mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction @@ -201,23 +207,23 @@ void InitParameter::CalcSphericalNormalNormal(libra::Vector<3>& destination, con // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product libra::Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); - double rotation_angle_of_normal_unit_vec = InitParameter::Generate1dUniform(0.0, libra::tau); + double rotation_angle_of_normal_unit_vec = InitMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation - double rotation_angle_of_mean_vec = InitParameter::Generate1dNormal(0.0, sigma_or_max_[1]); + double rotation_angle_of_mean_vec = InitMonteCarloParameters::Generate1dNormal(0.0, sigma_or_max_[1]); libra::Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction - ret_vec = InitParameter::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm + ret_vec = InitMonteCarloParameters::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { destination[i] = ret_vec[i]; } } -void InitParameter::GenerateSphericalNormalNormal() { +void InitMonteCarloParameters::GenerateSphericalNormalNormal() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < 2) { throw "Config parameters dimension unmatched."; @@ -234,7 +240,7 @@ void InitParameter::GenerateSphericalNormalNormal() { } } -void InitParameter::CalcQuaternionUniform(libra::Quaternion& destination) { +void InitMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destination) { // Perfectly Randomized libra::Quaternion libra::Vector<3> x_axis(0.0); x_axis[0] = 1.0; @@ -242,8 +248,8 @@ void InitParameter::CalcQuaternionUniform(libra::Quaternion& destination) { // A direction vector converted from the X-axis by a quaternion may follows the uniform distribution in full sphere. libra::Quaternion first_cnv; libra::Vector<3> x_axis_cnvd; - double theta = acos(1 - (1 - (-1)) * InitParameter::Generate1dUniform(0.0, 1.0)); - double phi = InitParameter::Generate1dUniform(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitMonteCarloParameters::Generate1dUniform(0, libra::tau); x_axis_cnvd[0] = sin(theta) * cos(phi); x_axis_cnvd[1] = sin(theta) * sin(phi); x_axis_cnvd[2] = cos(theta); @@ -256,7 +262,7 @@ void InitParameter::CalcQuaternionUniform(libra::Quaternion& destination) { first_cnv[3] = cos_angle_between; // Generate randomized rotation angle around the X-axis - double rotation_angle = InitParameter::Generate1dUniform(0.0, libra::tau); + double rotation_angle = InitMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion second_cnv(x_axis, rotation_angle); libra::Quaternion ret_q = first_cnv * second_cnv; @@ -266,7 +272,7 @@ void InitParameter::CalcQuaternionUniform(libra::Quaternion& destination) { } } -void InitParameter::GenerateQuaternionUniform() { +void InitMonteCarloParameters::GenerateQuaternionUniform() { const static int dim = 4; libra::Quaternion temp_q; CalcQuaternionUniform(temp_q); @@ -277,17 +283,17 @@ void InitParameter::GenerateQuaternionUniform() { } } -void InitParameter::CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma) { +void InitMonteCarloParameters::CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma) { // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere libra::Vector<3> rot_axis; - double theta = acos(1 - (1 - (-1)) * InitParameter::Generate1dUniform(0.0, 1.0)); - double phi = InitParameter::Generate1dUniform(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitMonteCarloParameters::Generate1dUniform(0, libra::tau); rot_axis[0] = sin(theta) * cos(phi); rot_axis[1] = sin(theta) * sin(phi); rot_axis[2] = cos(theta); - double rotation_angle = InitParameter::Generate1dNormal(0.0, theta_sigma); + double rotation_angle = InitMonteCarloParameters::Generate1dNormal(0.0, theta_sigma); libra::Quaternion ret_q(rot_axis, rotation_angle); for (int i = 0; i < 4; i++) { @@ -295,7 +301,7 @@ void InitParameter::CalcQuaternionNormal(libra::Quaternion& destination, double } } -void InitParameter::GenerateQuaternionNormal() { +void InitMonteCarloParameters::GenerateQuaternionNormal() { // mean_or_min_[0]: NA sigma_or_max_[0]: standard deviation of θ [rad] const static int dim = 4; if (sigma_or_max_.size() < 1) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index fa3c94786..7e99e7cc8 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -14,10 +14,10 @@ #include /** - * @class InitParameter + * @class InitMonteCarloParameters * @brief Initialized parameters for Monte-Carlo simulation */ -class InitParameter { +class InitMonteCarloParameters { public: /** * @enum RandomizationType @@ -36,10 +36,10 @@ class InitParameter { }; /** - * @fn InitParameter + * @fn InitMonteCarloParameters * @brief Constructor */ - InitParameter(); + InitMonteCarloParameters(); // Setter /** @@ -205,8 +205,8 @@ class InitParameter { }; template -void InitParameter::SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, - InitParameter::RandomizationType rnd_type) { +void InitMonteCarloParameters::SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, + InitMonteCarloParameters::RandomizationType rnd_type) { randomization_type_ = rnd_type; mean_or_min_.clear(); for (size_t i = 0; i < NumElement1; i++) { @@ -219,7 +219,7 @@ void InitParameter::SetRandomConfiguration(const libra::Vector& mea } template -void InitParameter::GetRandomizedVector(libra::Vector& destination) const { +void InitMonteCarloParameters::GetRandomizedVector(libra::Vector& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (NumElement > randomized_value_.size()) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 057fe9374..bb584374a 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -30,7 +30,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { enum Phase { FoundNothingYet, FoundSimulationObjectStr, FoundInitParameterStr }; for (auto so_dot_ip_str : so_dot_ip_str_vec) { - // Divide the string to SimulationObject and InitParameter + // Divide the string to SimulationObject and InitMonteCarloParameters Phase phase = FoundNothingYet; std::stringstream ss(so_dot_ip_str); std::string item, so_str, ip_str; @@ -50,32 +50,32 @@ MCSimExecutor* InitMCSim(std::string file_name) { } // Read Randomization type - InitParameter::RandomizationType rnd_type; + InitMonteCarloParameters::RandomizationType rnd_type; const static unsigned int buf_size = 256; char rnd_type_str[buf_size]; std::string key_name = so_dot_ip_str + MCSimExecutor::separator_ + "randomization_type"; ini_file.ReadChar(section, key_name.c_str(), buf_size, rnd_type_str); if (!strcmp(rnd_type_str, "NoRandomization")) - rnd_type = InitParameter::NoRandomization; + rnd_type = InitMonteCarloParameters::NoRandomization; else if (!strcmp(rnd_type_str, "CartesianUniform")) - rnd_type = InitParameter::CartesianUniform; + rnd_type = InitMonteCarloParameters::CartesianUniform; else if (!strcmp(rnd_type_str, "CartesianNormal")) - rnd_type = InitParameter::CartesianNormal; + rnd_type = InitMonteCarloParameters::CartesianNormal; else if (!strcmp(rnd_type_str, "CircularNormalUniform")) - rnd_type = InitParameter::CircularNormalUniform; + rnd_type = InitMonteCarloParameters::CircularNormalUniform; else if (!strcmp(rnd_type_str, "CircularNormalNormal")) - rnd_type = InitParameter::CircularNormalNormal; + rnd_type = InitMonteCarloParameters::CircularNormalNormal; else if (!strcmp(rnd_type_str, "SphericalNormalUniformUniform")) - rnd_type = InitParameter::SphericalNormalUniformUniform; + rnd_type = InitMonteCarloParameters::SphericalNormalUniformUniform; else if (!strcmp(rnd_type_str, "SphericalNormalNormal")) - rnd_type = InitParameter::SphericalNormalNormal; + rnd_type = InitMonteCarloParameters::SphericalNormalNormal; else if (!strcmp(rnd_type_str, "QuaternionUniform")) - rnd_type = InitParameter::QuaternionUniform; + rnd_type = InitMonteCarloParameters::QuaternionUniform; else if (!strcmp(rnd_type_str, "QuaternionNormal")) - rnd_type = InitParameter::QuaternionNormal; + rnd_type = InitMonteCarloParameters::QuaternionNormal; else - rnd_type = InitParameter::NoRandomization; + rnd_type = InitMonteCarloParameters::NoRandomization; // Read mean_or_min vector key_name = so_dot_ip_str + MCSimExecutor::separator_ + "mean_or_min"; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 62efb3ed0..90ed9b162 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -63,4 +63,4 @@ void MCSimExecutor::RandomizeAllParameters() { } } -void MCSimExecutor::SetSeed(unsigned long seed, bool is_deterministic) { InitParameter::SetSeed(seed, is_deterministic); } +void MCSimExecutor::SetSeed(unsigned long seed, bool is_deterministic) { InitMonteCarloParameters::SetSeed(seed, is_deterministic); } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index b40b3bc06..b416fb3f5 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -23,10 +23,10 @@ class MCSimExecutor { bool enabled_; //!< Flag to execute Monte-Carlo Simulation or not bool log_history_; //!< Flag to store the log for each case or not - std::map ip_list_; //!< List of InitParameters read from MCSim.ini + std::map ip_list_; //!< List of InitParameters read from MCSim.ini public: - static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitParameter in the initialization file + static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitMonteCarloParameters in the initialization file /** * @fn MCSimExecutor @@ -121,7 +121,7 @@ class MCSimExecutor { * @brief Add initialized parameter */ void AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type); + const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType rnd_type); /** * @fn RandomizeAllParameters @@ -161,16 +161,16 @@ void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name template void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitParameter::RandomizationType rnd_type) { + const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType rnd_type) { std::string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Register the parameter in ip_list if it is not registered yet - auto newparam = new InitParameter(); + auto newparam = new InitMonteCarloParameters(); newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, rnd_type); ip_list_[name] = newparam; } else { // Throw error if the parameter is already registered - throw "More than one definition of one InitParameter."; + throw "More than one definition of one InitMonteCarloParameters."; } } From 5e479928538dcb71999b7b6c8e5ddde21854a172 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:07:13 +0100 Subject: [PATCH 0915/1086] Fix function argument names --- .../initialize_monte_carlo_parameters.hpp | 6 ++--- .../initialize_monte_carlo_simulation.cpp | 24 +++++++++---------- .../monte_carlo_simulation_executor.hpp | 6 ++--- 3 files changed, 18 insertions(+), 18 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 7e99e7cc8..07bb9d16a 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -53,7 +53,7 @@ class InitMonteCarloParameters { */ template void SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, - RandomizationType rnd_type); + RandomizationType random_type); // Getter /** @@ -206,8 +206,8 @@ class InitMonteCarloParameters { template void InitMonteCarloParameters::SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, - InitMonteCarloParameters::RandomizationType rnd_type) { - randomization_type_ = rnd_type; + InitMonteCarloParameters::RandomizationType random_type) { + randomization_type_ = random_type; mean_or_min_.clear(); for (size_t i = 0; i < NumElement1; i++) { mean_or_min_.push_back(mean_or_min[i]); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index bb584374a..775ce4f9b 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -50,32 +50,32 @@ MCSimExecutor* InitMCSim(std::string file_name) { } // Read Randomization type - InitMonteCarloParameters::RandomizationType rnd_type; + InitMonteCarloParameters::RandomizationType random_type; const static unsigned int buf_size = 256; char rnd_type_str[buf_size]; std::string key_name = so_dot_ip_str + MCSimExecutor::separator_ + "randomization_type"; ini_file.ReadChar(section, key_name.c_str(), buf_size, rnd_type_str); if (!strcmp(rnd_type_str, "NoRandomization")) - rnd_type = InitMonteCarloParameters::NoRandomization; + random_type = InitMonteCarloParameters::NoRandomization; else if (!strcmp(rnd_type_str, "CartesianUniform")) - rnd_type = InitMonteCarloParameters::CartesianUniform; + random_type = InitMonteCarloParameters::CartesianUniform; else if (!strcmp(rnd_type_str, "CartesianNormal")) - rnd_type = InitMonteCarloParameters::CartesianNormal; + random_type = InitMonteCarloParameters::CartesianNormal; else if (!strcmp(rnd_type_str, "CircularNormalUniform")) - rnd_type = InitMonteCarloParameters::CircularNormalUniform; + random_type = InitMonteCarloParameters::CircularNormalUniform; else if (!strcmp(rnd_type_str, "CircularNormalNormal")) - rnd_type = InitMonteCarloParameters::CircularNormalNormal; + random_type = InitMonteCarloParameters::CircularNormalNormal; else if (!strcmp(rnd_type_str, "SphericalNormalUniformUniform")) - rnd_type = InitMonteCarloParameters::SphericalNormalUniformUniform; + random_type = InitMonteCarloParameters::SphericalNormalUniformUniform; else if (!strcmp(rnd_type_str, "SphericalNormalNormal")) - rnd_type = InitMonteCarloParameters::SphericalNormalNormal; + random_type = InitMonteCarloParameters::SphericalNormalNormal; else if (!strcmp(rnd_type_str, "QuaternionUniform")) - rnd_type = InitMonteCarloParameters::QuaternionUniform; + random_type = InitMonteCarloParameters::QuaternionUniform; else if (!strcmp(rnd_type_str, "QuaternionNormal")) - rnd_type = InitMonteCarloParameters::QuaternionNormal; + random_type = InitMonteCarloParameters::QuaternionNormal; else - rnd_type = InitMonteCarloParameters::NoRandomization; + random_type = InitMonteCarloParameters::NoRandomization; // Read mean_or_min vector key_name = so_dot_ip_str + MCSimExecutor::separator_ + "mean_or_min"; @@ -88,7 +88,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); // Write randomize setting - monte_carlo_simulator->AddInitParameter(so_str, ip_str, mean_or_min, sigma_or_max, rnd_type); + monte_carlo_simulator->AddInitParameter(so_str, ip_str, mean_or_min, sigma_or_max, random_type); } return monte_carlo_simulator; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index b416fb3f5..cb83d6c02 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -121,7 +121,7 @@ class MCSimExecutor { * @brief Add initialized parameter */ void AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType rnd_type); + const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type); /** * @fn RandomizeAllParameters @@ -161,12 +161,12 @@ void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name template void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType rnd_type) { + const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type) { std::string name = so_name + MCSimExecutor::separator_ + ip_name; if (ip_list_.find(name) == ip_list_.end()) { // Register the parameter in ip_list if it is not registered yet auto newparam = new InitMonteCarloParameters(); - newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, rnd_type); + newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, random_type); ip_list_[name] = newparam; } else { // Throw error if the parameter is already registered From 9173d0455afd567b4007b2d497be3283eea20966 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:13:51 +0100 Subject: [PATCH 0916/1086] Fix private variables and inline function --- .../monte_carlo_simulation_executor.cpp | 24 ++++----- .../monte_carlo_simulation_executor.hpp | 52 +++++++------------ 2 files changed, 31 insertions(+), 45 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 90ed9b162..1f71793d4 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -7,17 +7,17 @@ using std::string; -MCSimExecutor::MCSimExecutor(unsigned long long total_num_of_executions) : total_num_of_executions_(total_num_of_executions) { - num_of_executions_done_ = 0; - enabled_ = total_num_of_executions_ > 1 ? true : false; - log_history_ = !enabled_; +MCSimExecutor::MCSimExecutor(unsigned long long total_num_of_executions) : total_number_of_executions_(total_num_of_executions) { + number_of_executions_done_ = 0; + enabled_ = total_number_of_executions_ > 1 ? true : false; + save_log_history_flag_ = !enabled_; } bool MCSimExecutor::WillExecuteNextCase() { if (!enabled_) { - return (num_of_executions_done_ < 1); + return (number_of_executions_done_ < 1); } else { - return (num_of_executions_done_ < total_num_of_executions_); + return (number_of_executions_done_ < total_number_of_executions_); } } @@ -28,18 +28,18 @@ void MCSimExecutor::AtTheBeginningOfEachCase() { void MCSimExecutor::AtTheEndOfEachCase() { // Write CSV output of the simulation results - num_of_executions_done_++; + number_of_executions_done_++; } void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, double& destination) const { if (!enabled_) return; { string name = so_name + MCSimExecutor::separator_ + ip_name; - if (ip_list_.find(name) == ip_list_.end()) { + if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination } else { - ip_list_.at(name)->GetRandomizedScalar(destination); // cannot use operator[] since it is const map + init_parameter_list_.at(name)->GetRandomizedScalar(destination); // cannot use operator[] since it is const map } } } @@ -48,17 +48,17 @@ void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, l if (!enabled_) return; { string name = so_name + MCSimExecutor::separator_ + ip_name; - if (ip_list_.find(name) == ip_list_.end()) { + if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination } else { - ip_list_.at(name)->GetRandomizedQuaternion(destination); // cannot use operator[] since it is const map + init_parameter_list_.at(name)->GetRandomizedQuaternion(destination); // cannot use operator[] since it is const map } } } void MCSimExecutor::RandomizeAllParameters() { - for (auto ip : ip_list_) { + for (auto ip : init_parameter_list_) { ip.second->Randomize(); } } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index cb83d6c02..33d8578f7 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -18,12 +18,12 @@ */ class MCSimExecutor { private: - unsigned long long total_num_of_executions_; //!< Total number of execution simulation case - unsigned long long num_of_executions_done_; //!< Number of executed case - bool enabled_; //!< Flag to execute Monte-Carlo Simulation or not - bool log_history_; //!< Flag to store the log for each case or not + unsigned long long total_number_of_executions_; //!< Total number of execution simulation case + unsigned long long number_of_executions_done_; //!< Number of executed case + bool enabled_; //!< Flag to execute Monte-Carlo Simulation or not + bool save_log_history_flag_; //!< Flag to store the log for each case or not - std::map ip_list_; //!< List of InitParameters read from MCSim.ini + std::map init_parameter_list_; //!< List of InitMonteCarloParameters read from MCSim.ini public: static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitMonteCarloParameters in the initialization file @@ -39,17 +39,17 @@ class MCSimExecutor { * @fn Enable * @brief Set execute flag */ - inline void Enable(bool enabled); + inline void Enable(bool enabled) { enabled_ = enabled; } /** * @fn SetTotalNumOfExecutions * @brief Set total number of execution simulation case */ - inline void SetTotalNumOfExecutions(unsigned long long num_of_executions); + inline void SetTotalNumOfExecutions(unsigned long long num_of_executions) { total_number_of_executions_ = num_of_executions; } /** * @fn LogHistory * @brief Set log history flag */ - inline void LogHistory(bool set); + inline void LogHistory(bool set) { save_log_history_flag_ = set; } /** * @fn SetSeed * @brief Set seed of randomization. Use time infomation when is_deterministic = false. @@ -61,22 +61,25 @@ class MCSimExecutor { * @fn ISEnabled * @brief Return execute flag */ - inline bool IsEnabled() const; + inline bool IsEnabled() const { return enabled_; } /** * @fn GetTotalNumOfExecutions * @brief Return total number of execution simulation case */ - inline unsigned long long GetTotalNumOfExecutions() const; + inline unsigned long long GetTotalNumOfExecutions() const { return total_number_of_executions_; } /** * @fn GetNumOfExecutionsDone * @brief Return number of executed case */ - inline unsigned long long GetNumOfExecutionsDone() const; + inline unsigned long long GetNumOfExecutionsDone() const { return number_of_executions_done_; } /** * @fn LogHistory * @brief Return log history flag */ - inline bool LogHistory() const; + inline bool LogHistory() const { + // Save log if MCSim is disabled or LogHistory=ENABLED + return (!enabled_ || save_log_history_flag_); + } /** * @fn GetInitParameterVec * @brief Get randomized vector value and store it in dest_vec @@ -130,32 +133,15 @@ class MCSimExecutor { void RandomizeAllParameters(); }; -void MCSimExecutor::Enable(bool enabled) { enabled_ = enabled; } - -bool MCSimExecutor::IsEnabled() const { return enabled_; } - -void MCSimExecutor::SetTotalNumOfExecutions(unsigned long long num_of_executions) { total_num_of_executions_ = num_of_executions; } - -unsigned long long MCSimExecutor::GetTotalNumOfExecutions() const { return total_num_of_executions_; } - -inline unsigned long long MCSimExecutor::GetNumOfExecutionsDone() const { return num_of_executions_done_; } - -bool MCSimExecutor::LogHistory() const { - // Save log if MCSim is disabled or LogHistory=ENABLED - return (!enabled_ || log_history_); -} - -void MCSimExecutor::LogHistory(bool set) { log_history_ = set; } - template void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const { if (!enabled_) return; std::string name = so_name + MCSimExecutor::separator_ + ip_name; - if (ip_list_.find(name) == ip_list_.end()) { + if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without update the destination } else { - ip_list_.at(name)->GetRandomizedVector(destination); // cannot use operator[] since it is const map + init_parameter_list_.at(name)->GetRandomizedVector(destination); // cannot use operator[] since it is const map } } @@ -163,11 +149,11 @@ template void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type) { std::string name = so_name + MCSimExecutor::separator_ + ip_name; - if (ip_list_.find(name) == ip_list_.end()) { + if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Register the parameter in ip_list if it is not registered yet auto newparam = new InitMonteCarloParameters(); newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, random_type); - ip_list_[name] = newparam; + init_parameter_list_[name] = newparam; } else { // Throw error if the parameter is already registered throw "More than one definition of one InitMonteCarloParameters."; From 09093dc400dc98a6d5141bdfc6f48d835a415a67 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:15:11 +0100 Subject: [PATCH 0917/1086] Rename class --- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/attitude_rk4.hpp | 2 +- src/simulation/case/simulation_case.cpp | 2 +- src/simulation/case/simulation_case.hpp | 2 +- .../initialize_monte_carlo_simulation.cpp | 12 +++++------ .../initialize_monte_carlo_simulation.hpp | 2 +- .../monte_carlo_simulation_executor.cpp | 21 ++++++++++--------- .../monte_carlo_simulation_executor.hpp | 19 +++++++++-------- .../simulation_object.cpp | 7 ++++--- .../simulation_object.hpp | 14 +++++++------ 12 files changed, 46 insertions(+), 41 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index aaf719c05..5fecfc4b9 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -42,7 +42,7 @@ std::string Attitude::GetLogValue() const { return str_tmp; } -void Attitude::SetParameters(const MCSimExecutor& mc_simulator) { GetInitParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); } +void Attitude::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { GetInitParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); } void Attitude::CalcAngularMomentum(void) { angular_momentum_spacecraft_b_Nms_ = inertia_tensor_kgm2_ * angular_velocity_b_rad_s_; diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 84f1e6d75..8019ca4a1 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -109,7 +109,7 @@ class Attitude : public ILoggable, public SimulationObject { virtual std::string GetLogValue() const; // SimulationObject for McSim - virtual void SetParameters(const MCSimExecutor& mc_simulator); + virtual void SetParameters(const MonteCarloSimulationExecutor& mc_simulator); protected: bool is_calc_enabled_ = true; //!< Calculation flag diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index 2f27eb25d..ce7255d9b 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -26,7 +26,7 @@ AttitudeRk4::AttitudeRk4(const libra::Vector<3>& angular_velocity_b_rad_s, const AttitudeRk4::~AttitudeRk4() {} -void AttitudeRk4::SetParameters(const MCSimExecutor& mc_simulator) { +void AttitudeRk4::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { Attitude::SetParameters(mc_simulator); GetInitParameterVec(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index dc7bc2d54..bf838dd1f 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -45,7 +45,7 @@ class AttitudeRk4 : public Attitude { * @brief Set parameters for Monte-Carlo simulation * @param [in] mc_simulator: Monte-Carlo simulation executor */ - virtual void SetParameters(const MCSimExecutor& mc_simulator); + virtual void SetParameters(const MonteCarloSimulationExecutor& mc_simulator); private: double current_propagation_time_s_; //!< current time [sec] diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 86140ffbd..af86144f9 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -24,7 +24,7 @@ SimulationCase::SimulationCase(std::string ini_base) { sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); global_environment_ = new GlobalEnvironment(&sim_config_); } -SimulationCase::SimulationCase(std::string ini_base, const MCSimExecutor& monte_carlo_simulator, const std::string log_path) { +SimulationCase::SimulationCase(std::string ini_base, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { IniAccess simbase_ini = IniAccess(ini_base); const char* section = "SIMULATION_SETTINGS"; sim_config_.initialize_base_file_name_ = ini_base; diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 93015f9b1..0388a6b6d 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -28,7 +28,7 @@ class SimulationCase : public ILoggable { * @fn SimulationCase * @brief Constructor for Monte-Carlo Simulation */ - SimulationCase(std::string ini_base, const MCSimExecutor& monte_carlo_simulator, std::string log_path); + SimulationCase(std::string ini_base, const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string log_path); /** * @fn ~SimulationCase * @brief Destructor diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 775ce4f9b..55eee07a4 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -10,13 +10,13 @@ #define MAX_CHAR_NUM 256 -MCSimExecutor* InitMCSim(std::string file_name) { +MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { IniAccess ini_file(file_name); const char* section = "MONTE_CARLO_EXECUTION"; unsigned long long total_num_of_executions = ini_file.ReadInt(section, "number_of_executions"); - MCSimExecutor* monte_carlo_simulator = new MCSimExecutor(total_num_of_executions); + MonteCarloSimulationExecutor* monte_carlo_simulator = new MonteCarloSimulationExecutor(total_num_of_executions); bool enable = ini_file.ReadEnable(section, "monte_carlo_enable"); monte_carlo_simulator->Enable(enable); @@ -34,7 +34,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { Phase phase = FoundNothingYet; std::stringstream ss(so_dot_ip_str); std::string item, so_str, ip_str; - while (getline(ss, item, MCSimExecutor::separator_)) { + while (getline(ss, item, MonteCarloSimulationExecutor::separator_)) { if (!item.empty()) { if (phase == FoundNothingYet) { phase = FoundSimulationObjectStr; @@ -53,7 +53,7 @@ MCSimExecutor* InitMCSim(std::string file_name) { InitMonteCarloParameters::RandomizationType random_type; const static unsigned int buf_size = 256; char rnd_type_str[buf_size]; - std::string key_name = so_dot_ip_str + MCSimExecutor::separator_ + "randomization_type"; + std::string key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "randomization_type"; ini_file.ReadChar(section, key_name.c_str(), buf_size, rnd_type_str); if (!strcmp(rnd_type_str, "NoRandomization")) @@ -78,12 +78,12 @@ MCSimExecutor* InitMCSim(std::string file_name) { random_type = InitMonteCarloParameters::NoRandomization; // Read mean_or_min vector - key_name = so_dot_ip_str + MCSimExecutor::separator_ + "mean_or_min"; + key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "mean_or_min"; libra::Vector<3> mean_or_min; ini_file.ReadVector(section, key_name.c_str(), mean_or_min); // Read sigma_or_max vector - key_name = so_dot_ip_str + MCSimExecutor::separator_ + "sigma_or_max"; + key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "sigma_or_max"; libra::Vector<3> sigma_or_max; ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp index c667c9583..8a571fc63 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp @@ -13,6 +13,6 @@ * @fn InitMCSim * @brief Initialize function for Monte-Carlo Simulator */ -MCSimExecutor* InitMCSim(std::string file_name); +MonteCarloSimulationExecutor* InitMCSim(std::string file_name); #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_HPP_ diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 1f71793d4..7e746e291 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -7,13 +7,14 @@ using std::string; -MCSimExecutor::MCSimExecutor(unsigned long long total_num_of_executions) : total_number_of_executions_(total_num_of_executions) { +MonteCarloSimulationExecutor::MonteCarloSimulationExecutor(unsigned long long total_num_of_executions) + : total_number_of_executions_(total_num_of_executions) { number_of_executions_done_ = 0; enabled_ = total_number_of_executions_ > 1 ? true : false; save_log_history_flag_ = !enabled_; } -bool MCSimExecutor::WillExecuteNextCase() { +bool MonteCarloSimulationExecutor::WillExecuteNextCase() { if (!enabled_) { return (number_of_executions_done_ < 1); } else { @@ -21,20 +22,20 @@ bool MCSimExecutor::WillExecuteNextCase() { } } -void MCSimExecutor::AtTheBeginningOfEachCase() { +void MonteCarloSimulationExecutor::AtTheBeginningOfEachCase() { // Write CSV output of the randomization results ; } -void MCSimExecutor::AtTheEndOfEachCase() { +void MonteCarloSimulationExecutor::AtTheEndOfEachCase() { // Write CSV output of the simulation results number_of_executions_done_++; } -void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, double& destination) const { +void MonteCarloSimulationExecutor::GetInitParameterDouble(string so_name, string ip_name, double& destination) const { if (!enabled_) return; { - string name = so_name + MCSimExecutor::separator_ + ip_name; + string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination @@ -44,10 +45,10 @@ void MCSimExecutor::GetInitParameterDouble(string so_name, string ip_name, doubl } } -void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { +void MonteCarloSimulationExecutor::GetInitParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { if (!enabled_) return; { - string name = so_name + MCSimExecutor::separator_ + ip_name; + string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination @@ -57,10 +58,10 @@ void MCSimExecutor::GetInitParameterQuaternion(string so_name, string ip_name, l } } -void MCSimExecutor::RandomizeAllParameters() { +void MonteCarloSimulationExecutor::RandomizeAllParameters() { for (auto ip : init_parameter_list_) { ip.second->Randomize(); } } -void MCSimExecutor::SetSeed(unsigned long seed, bool is_deterministic) { InitMonteCarloParameters::SetSeed(seed, is_deterministic); } +void MonteCarloSimulationExecutor::SetSeed(unsigned long seed, bool is_deterministic) { InitMonteCarloParameters::SetSeed(seed, is_deterministic); } diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 33d8578f7..6727c7ca5 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -13,10 +13,10 @@ #include "initialize_monte_carlo_parameters.hpp" /** - * @class MCSimExecutor + * @class MonteCarloSimulationExecutor * @brief Monte-Carlo Simulation Executor class */ -class MCSimExecutor { +class MonteCarloSimulationExecutor { private: unsigned long long total_number_of_executions_; //!< Total number of execution simulation case unsigned long long number_of_executions_done_; //!< Number of executed case @@ -29,10 +29,10 @@ class MCSimExecutor { static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitMonteCarloParameters in the initialization file /** - * @fn MCSimExecutor + * @fn MonteCarloSimulationExecutor * @brief Constructor */ - MCSimExecutor(unsigned long long total_num_of_executions); + MonteCarloSimulationExecutor(unsigned long long total_num_of_executions); // Setter /** @@ -134,9 +134,9 @@ class MCSimExecutor { }; template -void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const { +void MonteCarloSimulationExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const { if (!enabled_) return; - std::string name = so_name + MCSimExecutor::separator_ + ip_name; + std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without update the destination @@ -146,9 +146,10 @@ void MCSimExecutor::GetInitParameterVec(std::string so_name, std::string ip_name } template -void MCSimExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type) { - std::string name = so_name + MCSimExecutor::separator_ + ip_name; +void MonteCarloSimulationExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, + InitMonteCarloParameters::RandomizationType random_type) { + std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Register the parameter in ip_list if it is not registered yet auto newparam = new InitMonteCarloParameters(); diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index 768120d92..ae86f1bd4 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -26,17 +26,18 @@ SimulationObject::~SimulationObject() { SimulationObject::ojbect_list_.erase(name_); } -void SimulationObject::SetAllParameters(const MCSimExecutor& monte_carlo_simulator) { +void SimulationObject::SetAllParameters(const MonteCarloSimulationExecutor& monte_carlo_simulator) { for (auto so : SimulationObject::ojbect_list_) { so.second->SetParameters(monte_carlo_simulator); } } -void SimulationObject::GetInitParameterDouble(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const { +void SimulationObject::GetInitParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + double& destination) const { monte_carlo_simulator.GetInitParameterDouble(name_, ip_name, destination); } -void SimulationObject::GetInitParameterQuaternion(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, +void SimulationObject::GetInitParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, libra::Quaternion& destination) const { monte_carlo_simulator.GetInitParameterQuaternion(name_, ip_name, destination); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index f3c040f9a..4df1fd11d 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -39,31 +39,33 @@ class SimulationObject { * @brief Get randomized vector value and store it in destination */ template - void GetInitParameterVec(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, libra::Vector& destination) const; + void GetInitParameterVec(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Vector& destination) const; /** * @fn GetInitParameterDouble * @brief Get randomized value and store it in destination */ - void GetInitParameterDouble(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; + void GetInitParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; /** * @fn GetInitParameterQuaternion * @brief Get randomized quaternion and store it in destination */ - void GetInitParameterQuaternion(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, libra::Quaternion& destination) const; + void GetInitParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Quaternion& destination) const; /** * @fn SetParameters * @brief Virtual function to set the randomized results to target variables */ - virtual void SetParameters(const MCSimExecutor& monte_carlo_simulator) = 0; + virtual void SetParameters(const MonteCarloSimulationExecutor& monte_carlo_simulator) = 0; /** * @fn SetAllParameters * @brief Execute all SetParameter function for all SimulationObject instance */ - static void SetAllParameters(const MCSimExecutor& monte_carlo_simulator); + static void SetAllParameters(const MonteCarloSimulationExecutor& monte_carlo_simulator); private: std::string name_; //!< Name to distinguish the target variable in initialize file for Monte-Carlo simulation @@ -75,7 +77,7 @@ class SimulationObject { * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitParameterVec(const MCSimExecutor& monte_carlo_simulator, std::string ip_name, +void SimulationObject::GetInitParameterVec(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, libra::Vector& destination) const { monte_carlo_simulator.GetInitParameterVec(name_, ip_name, destination); } From a96cd8521c9ccddf06fdd7ceea0e425b2ce2d083 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:21:20 +0100 Subject: [PATCH 0918/1086] Fix public function name --- src/dynamics/attitude/attitude.cpp | 4 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/simulation/case/simulation_case.cpp | 4 +- .../initialize_monte_carlo_simulation.cpp | 6 +-- .../monte_carlo_simulation_executor.cpp | 4 +- .../monte_carlo_simulation_executor.hpp | 51 ++++++++++--------- .../simulation_object.cpp | 12 ++--- .../simulation_object.hpp | 24 ++++----- 8 files changed, 55 insertions(+), 52 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 5fecfc4b9..2fb9bf135 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -42,7 +42,9 @@ std::string Attitude::GetLogValue() const { return str_tmp; } -void Attitude::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { GetInitParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); } +void Attitude::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { + GetInitMonteCarloParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); +} void Attitude::CalcAngularMomentum(void) { angular_momentum_spacecraft_b_Nms_ = inertia_tensor_kgm2_ * angular_velocity_b_rad_s_; diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index ce7255d9b..d9d9ae818 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -28,7 +28,7 @@ AttitudeRk4::~AttitudeRk4() {} void AttitudeRk4::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { Attitude::SetParameters(mc_simulator); - GetInitParameterVec(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); + GetInitMonteCarloParameterVector(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index af86144f9..38000a1ae 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -29,9 +29,9 @@ SimulationCase::SimulationCase(std::string ini_base, const MonteCarloSimulationE const char* section = "SIMULATION_SETTINGS"; sim_config_.initialize_base_file_name_ = ini_base; // Log for Monte Carlo Simulation - std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumOfExecutionsDone()) + ".csv"; + std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; // ToDo: Consider that `enable_inilog = false` is fine or not? - sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, monte_carlo_simulator.LogHistory()); + sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 55eee07a4..8bf0c7829 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -19,10 +19,10 @@ MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { MonteCarloSimulationExecutor* monte_carlo_simulator = new MonteCarloSimulationExecutor(total_num_of_executions); bool enable = ini_file.ReadEnable(section, "monte_carlo_enable"); - monte_carlo_simulator->Enable(enable); + monte_carlo_simulator->SetEnable(enable); bool log_history = ini_file.ReadEnable(section, "log_enable"); - monte_carlo_simulator->LogHistory(log_history); + monte_carlo_simulator->SetSaveLogHistoryFlag(log_history); section = "MONTE_CARLO_RANDOMIZATION"; std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "parameter"); @@ -88,7 +88,7 @@ MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); // Write randomize setting - monte_carlo_simulator->AddInitParameter(so_str, ip_str, mean_or_min, sigma_or_max, random_type); + monte_carlo_simulator->AddInitMonteCarloParameter(so_str, ip_str, mean_or_min, sigma_or_max, random_type); } return monte_carlo_simulator; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index 7e746e291..aaf4f9169 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -32,7 +32,7 @@ void MonteCarloSimulationExecutor::AtTheEndOfEachCase() { number_of_executions_done_++; } -void MonteCarloSimulationExecutor::GetInitParameterDouble(string so_name, string ip_name, double& destination) const { +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_name, string ip_name, double& destination) const { if (!enabled_) return; { string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; @@ -45,7 +45,7 @@ void MonteCarloSimulationExecutor::GetInitParameterDouble(string so_name, string } } -void MonteCarloSimulationExecutor::GetInitParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { if (!enabled_) return; { string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 6727c7ca5..0db2d73ad 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -39,17 +39,17 @@ class MonteCarloSimulationExecutor { * @fn Enable * @brief Set execute flag */ - inline void Enable(bool enabled) { enabled_ = enabled; } + inline void SetEnable(bool enabled) { enabled_ = enabled; } /** - * @fn SetTotalNumOfExecutions + * @fn SetTotalNumberOfExecutions * @brief Set total number of execution simulation case */ - inline void SetTotalNumOfExecutions(unsigned long long num_of_executions) { total_number_of_executions_ = num_of_executions; } + inline void SetTotalNumberOfExecutions(unsigned long long number_of_executions) { total_number_of_executions_ = number_of_executions; } /** - * @fn LogHistory + * @fn GetSaveLogHistoryFlag * @brief Set log history flag */ - inline void LogHistory(bool set) { save_log_history_flag_ = set; } + inline void SetSaveLogHistoryFlag(bool set) { save_log_history_flag_ = set; } /** * @fn SetSeed * @brief Set seed of randomization. Use time infomation when is_deterministic = false. @@ -63,39 +63,39 @@ class MonteCarloSimulationExecutor { */ inline bool IsEnabled() const { return enabled_; } /** - * @fn GetTotalNumOfExecutions + * @fn GetTotalNumberOfExecutions * @brief Return total number of execution simulation case */ - inline unsigned long long GetTotalNumOfExecutions() const { return total_number_of_executions_; } + inline unsigned long long GetTotalNumberOfExecutions() const { return total_number_of_executions_; } /** - * @fn GetNumOfExecutionsDone + * @fn GetNumberOfExecutionsDone * @brief Return number of executed case */ - inline unsigned long long GetNumOfExecutionsDone() const { return number_of_executions_done_; } + inline unsigned long long GetNumberOfExecutionsDone() const { return number_of_executions_done_; } /** - * @fn LogHistory + * @fn GetSaveLogHistoryFlag * @brief Return log history flag */ - inline bool LogHistory() const { - // Save log if MCSim is disabled or LogHistory=ENABLED + inline bool GetSaveLogHistoryFlag() const { + // Save log if MCSim is disabled or GetSaveLogHistoryFlag=ENABLED return (!enabled_ || save_log_history_flag_); } /** - * @fn GetInitParameterVec + * @fn GetInitMonteCarloParameterVector * @brief Get randomized vector value and store it in dest_vec */ template - void GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const; + void GetInitMonteCarloParameterVector(std::string so_name, std::string ip_name, libra::Vector& destination) const; /** - * @fn GetInitParameterDouble + * @fn GetInitMonteCarloParameterDouble * @brief Get randomized value and store it in dest */ - void GetInitParameterDouble(std::string so_name, std::string ip_name, double& destination) const; + void GetInitMonteCarloParameterDouble(std::string so_name, std::string ip_name, double& destination) const; /** - * @fn GetInitParameterQuaternion + * @fn GetInitMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in dest_quat */ - void GetInitParameterQuaternion(std::string so_name, std::string ip_name, libra::Quaternion& destination) const; + void GetInitMonteCarloParameterQuaternion(std::string so_name, std::string ip_name, libra::Quaternion& destination) const; // Calculation /** @@ -120,11 +120,11 @@ class MonteCarloSimulationExecutor { template /** - * @fn AddInitParameter + * @fn AddInitMonteCarloParameter * @brief Add initialized parameter */ - void AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type); + void AddInitMonteCarloParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type); /** * @fn RandomizeAllParameters @@ -134,7 +134,8 @@ class MonteCarloSimulationExecutor { }; template -void MonteCarloSimulationExecutor::GetInitParameterVec(std::string so_name, std::string ip_name, libra::Vector& destination) const { +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string so_name, std::string ip_name, + libra::Vector& destination) const { if (!enabled_) return; std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { @@ -146,9 +147,9 @@ void MonteCarloSimulationExecutor::GetInitParameterVec(std::string so_name, std: } template -void MonteCarloSimulationExecutor::AddInitParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, - InitMonteCarloParameters::RandomizationType random_type) { +void MonteCarloSimulationExecutor::AddInitMonteCarloParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, + InitMonteCarloParameters::RandomizationType random_type) { std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Register the parameter in ip_list if it is not registered yet diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index ae86f1bd4..73992d5aa 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -32,12 +32,12 @@ void SimulationObject::SetAllParameters(const MonteCarloSimulationExecutor& mont } } -void SimulationObject::GetInitParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - double& destination) const { - monte_carlo_simulator.GetInitParameterDouble(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + double& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterDouble(name_, ip_name, destination); } -void SimulationObject::GetInitParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Quaternion& destination) const { - monte_carlo_simulator.GetInitParameterQuaternion(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Quaternion& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterQuaternion(name_, ip_name, destination); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 4df1fd11d..c4f27d6d7 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -35,25 +35,25 @@ class SimulationObject { virtual ~SimulationObject(); /** - * @fn GetInitParameterVec + * @fn GetInitMonteCarloParameterVector * @brief Get randomized vector value and store it in destination */ template - void GetInitParameterVec(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Vector& destination) const; + void GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Vector& destination) const; /** - * @fn GetInitParameterDouble + * @fn GetInitMonteCarloParameterDouble * @brief Get randomized value and store it in destination */ - void GetInitParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; + void GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; /** - * @fn GetInitParameterQuaternion + * @fn GetInitMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in destination */ - void GetInitParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Quaternion& destination) const; + void GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Quaternion& destination) const; /** * @fn SetParameters @@ -73,13 +73,13 @@ class SimulationObject { }; /** - * @fn GetInitParameterVec + * @fn GetInitMonteCarloParameterVector * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitParameterVec(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Vector& destination) const { - monte_carlo_simulator.GetInitParameterVec(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + libra::Vector& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterVector(name_, ip_name, destination); } #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ From 9d47536576bdee5f74e7c21c74e134e821eec515 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:22:22 +0100 Subject: [PATCH 0919/1086] Fix function argument name --- .../monte_carlo_simulation_executor.cpp | 10 ++++++---- .../monte_carlo_simulation_executor.hpp | 18 ++++++++++-------- .../simulation_object.cpp | 12 ++++++------ .../simulation_object.hpp | 13 +++++++------ 4 files changed, 29 insertions(+), 24 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index aaf4f9169..d4b2d78db 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -32,10 +32,11 @@ void MonteCarloSimulationExecutor::AtTheEndOfEachCase() { number_of_executions_done_++; } -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_name, string ip_name, double& destination) const { +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_name, string init_monte_carlo_parameter_name, + double& destination) const { if (!enabled_) return; { - string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; + string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination @@ -45,10 +46,11 @@ void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_na } } -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterQuaternion(string so_name, string ip_name, libra::Quaternion& destination) const { +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterQuaternion(string so_name, string init_monte_carlo_parameter_name, + libra::Quaternion& destination) const { if (!enabled_) return; { - string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; + string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without any update of destination diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 0db2d73ad..426168a08 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -85,17 +85,18 @@ class MonteCarloSimulationExecutor { * @brief Get randomized vector value and store it in dest_vec */ template - void GetInitMonteCarloParameterVector(std::string so_name, std::string ip_name, libra::Vector& destination) const; + void GetInitMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, + libra::Vector& destination) const; /** * @fn GetInitMonteCarloParameterDouble * @brief Get randomized value and store it in dest */ - void GetInitMonteCarloParameterDouble(std::string so_name, std::string ip_name, double& destination) const; + void GetInitMonteCarloParameterDouble(std::string so_name, std::string init_monte_carlo_parameter_name, double& destination) const; /** * @fn GetInitMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in dest_quat */ - void GetInitMonteCarloParameterQuaternion(std::string so_name, std::string ip_name, libra::Quaternion& destination) const; + void GetInitMonteCarloParameterQuaternion(std::string so_name, std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const; // Calculation /** @@ -123,7 +124,7 @@ class MonteCarloSimulationExecutor { * @fn AddInitMonteCarloParameter * @brief Add initialized parameter */ - void AddInitMonteCarloParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, + void AddInitMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type); /** @@ -134,10 +135,10 @@ class MonteCarloSimulationExecutor { }; template -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string so_name, std::string ip_name, +void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, libra::Vector& destination) const { if (!enabled_) return; - std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; + std::string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Not registered in ip_list(Not defined in MCSim.ini) return; // return without update the destination @@ -147,10 +148,11 @@ void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string } template -void MonteCarloSimulationExecutor::AddInitMonteCarloParameter(std::string so_name, std::string ip_name, const libra::Vector& mean_or_min, +void MonteCarloSimulationExecutor::AddInitMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, + const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type) { - std::string name = so_name + MonteCarloSimulationExecutor::separator_ + ip_name; + std::string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Register the parameter in ip_list if it is not registered yet auto newparam = new InitMonteCarloParameters(); diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index 73992d5aa..b5cb96a91 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -32,12 +32,12 @@ void SimulationObject::SetAllParameters(const MonteCarloSimulationExecutor& mont } } -void SimulationObject::GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - double& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterDouble(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, double& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterDouble(name_, init_monte_carlo_parameter_name, destination); } -void SimulationObject::GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Quaternion& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterQuaternion(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterQuaternion(name_, init_monte_carlo_parameter_name, destination); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index c4f27d6d7..bc77a4d8a 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -39,20 +39,21 @@ class SimulationObject { * @brief Get randomized vector value and store it in destination */ template - void GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + void GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, libra::Vector& destination) const; /** * @fn GetInitMonteCarloParameterDouble * @brief Get randomized value and store it in destination */ - void GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, double& destination) const; + void GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, + double& destination) const; /** * @fn GetInitMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in destination */ - void GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, + void GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const; /** @@ -77,9 +78,9 @@ class SimulationObject { * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string ip_name, - libra::Vector& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterVector(name_, ip_name, destination); +void SimulationObject::GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, libra::Vector& destination) const { + monte_carlo_simulator.GetInitMonteCarloParameterVector(name_, init_monte_carlo_parameter_name, destination); } #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ From d97d12afa89ef9d26331ea0a2babea53c22c8294 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:24:08 +0100 Subject: [PATCH 0920/1086] Fix InitializedMonteCarloParameter --- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 106 +++++++++--------- .../initialize_monte_carlo_parameters.hpp | 15 +-- .../initialize_monte_carlo_simulation.cpp | 26 ++--- .../monte_carlo_simulation_executor.cpp | 12 +- .../monte_carlo_simulation_executor.hpp | 42 +++---- .../simulation_object.cpp | 13 ++- .../simulation_object.hpp | 27 ++--- 9 files changed, 126 insertions(+), 119 deletions(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 2fb9bf135..5b07380e9 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -43,7 +43,7 @@ std::string Attitude::GetLogValue() const { } void Attitude::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { - GetInitMonteCarloParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); + GetInitializedMonteCarloParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); } void Attitude::CalcAngularMomentum(void) { diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index d9d9ae818..b2bc62f67 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -28,7 +28,7 @@ AttitudeRk4::~AttitudeRk4() {} void AttitudeRk4::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { Attitude::SetParameters(mc_simulator); - GetInitMonteCarloParameterVector(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); + GetInitializedMonteCarloParameterVector(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 19195b6a6..c4a26c8d0 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -9,18 +9,18 @@ using namespace std; -random_device InitMonteCarloParameters::randomizer_; -mt19937 InitMonteCarloParameters::mt_; -uniform_real_distribution<>* InitMonteCarloParameters::uniform_distribution_; -normal_distribution<>* InitMonteCarloParameters::normal_distribution_; +random_device InitializedMonteCarloParameters::randomizer_; +mt19937 InitializedMonteCarloParameters::mt_; +uniform_real_distribution<>* InitializedMonteCarloParameters::uniform_distribution_; +normal_distribution<>* InitializedMonteCarloParameters::normal_distribution_; -InitMonteCarloParameters::InitMonteCarloParameters() { +InitializedMonteCarloParameters::InitializedMonteCarloParameters() { // Generate object when the first execution static bool initial_setup_done = false; if (!initial_setup_done) { SetSeed(); - InitMonteCarloParameters::uniform_distribution_ = new uniform_real_distribution<>(0.0, 1.0); - InitMonteCarloParameters::normal_distribution_ = new normal_distribution<>(0.0, 1.0); + InitializedMonteCarloParameters::uniform_distribution_ = new uniform_real_distribution<>(0.0, 1.0); + InitializedMonteCarloParameters::normal_distribution_ = new normal_distribution<>(0.0, 1.0); initial_setup_done = true; } @@ -28,15 +28,15 @@ InitMonteCarloParameters::InitMonteCarloParameters() { randomization_type_ = NoRandomization; } -void InitMonteCarloParameters::SetSeed(unsigned long seed, bool is_deterministic) { +void InitializedMonteCarloParameters::SetSeed(unsigned long seed, bool is_deterministic) { if (is_deterministic) { - InitMonteCarloParameters::mt_.seed(seed); + InitializedMonteCarloParameters::mt_.seed(seed); } else { - InitMonteCarloParameters::mt_.seed(InitMonteCarloParameters::randomizer_()); + InitializedMonteCarloParameters::mt_.seed(InitializedMonteCarloParameters::randomizer_()); } } -void InitMonteCarloParameters::GetRandomizedScalar(double& destination) const { +void InitializedMonteCarloParameters::GetRandomizedScalar(double& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (1 > randomized_value_.size()) { @@ -46,7 +46,7 @@ void InitMonteCarloParameters::GetRandomizedScalar(double& destination) const { } } -void InitMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& destination) const { +void InitializedMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (4 > randomized_value_.size()) { @@ -60,7 +60,7 @@ void InitMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& destin destination.Normalize(); } -void InitMonteCarloParameters::Randomize() { +void InitializedMonteCarloParameters::Randomize() { switch (randomization_type_) { case NoRandomization: GenerateNoRandomization(); @@ -94,42 +94,42 @@ void InitMonteCarloParameters::Randomize() { } } -double InitMonteCarloParameters::Generate1dUniform(double lb, double ub) { - return lb + (*InitMonteCarloParameters::uniform_distribution_)(InitMonteCarloParameters::mt_) * (ub - lb); +double InitializedMonteCarloParameters::Generate1dUniform(double lb, double ub) { + return lb + (*InitializedMonteCarloParameters::uniform_distribution_)(InitializedMonteCarloParameters::mt_) * (ub - lb); } -double InitMonteCarloParameters::Generate1dNormal(double mean, double std) { - return mean + (*InitMonteCarloParameters::normal_distribution_)(InitMonteCarloParameters::mt_) * (std); +double InitializedMonteCarloParameters::Generate1dNormal(double mean, double std) { + return mean + (*InitializedMonteCarloParameters::normal_distribution_)(InitializedMonteCarloParameters::mt_) * (std); } -void InitMonteCarloParameters::GenerateNoRandomization() { randomized_value_.clear(); } +void InitializedMonteCarloParameters::GenerateNoRandomization() { randomized_value_.clear(); } -void InitMonteCarloParameters::GenerateCartesianUniform() { +void InitializedMonteCarloParameters::GenerateCartesianUniform() { // Random variables following a uniform distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitMonteCarloParameters::Generate1dUniform(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitializedMonteCarloParameters::Generate1dUniform(mean_or_min_[i], sigma_or_max_[i])); } } -void InitMonteCarloParameters::GenerateCartesianNormal() { +void InitializedMonteCarloParameters::GenerateCartesianNormal() { // Random variables following a normal distribution in Cartesian frame randomized_value_.clear(); for (unsigned int i = 0; i < mean_or_min_.size(); i++) { - randomized_value_.push_back(InitMonteCarloParameters::Generate1dNormal(mean_or_min_[i], sigma_or_max_[i])); + randomized_value_.push_back(InitializedMonteCarloParameters::Generate1dNormal(mean_or_min_[i], sigma_or_max_[i])); } } -void InitMonteCarloParameters::CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, - double theta_max) { +void InitializedMonteCarloParameters::CalcCircularNormalUniform(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_min, + double theta_max) { // r follows normal distribution, and θ follows uniform distribution in Circular frame - double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); - double theta = InitMonteCarloParameters::Generate1dUniform(theta_min, theta_max); + double r = InitializedMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = InitializedMonteCarloParameters::Generate1dUniform(theta_min, theta_max); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitMonteCarloParameters::GenerateCircularNormalUniform() { +void InitializedMonteCarloParameters::GenerateCircularNormalUniform() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -143,16 +143,16 @@ void InitMonteCarloParameters::GenerateCircularNormalUniform() { } } -void InitMonteCarloParameters::CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, - double theta_sigma) { +void InitializedMonteCarloParameters::CalcCircularNormalNormal(libra::Vector<2>& destination, double r_mean, double r_sigma, double theta_mean, + double theta_sigma) { // r and θ follow normal distribution in Circular frame - double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); - double theta = InitMonteCarloParameters::Generate1dNormal(theta_mean, theta_sigma); + double r = InitializedMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = InitializedMonteCarloParameters::Generate1dNormal(theta_mean, theta_sigma); destination[0] = r * cos(theta); destination[1] = r * sin(theta); } -void InitMonteCarloParameters::GenerateCircularNormalNormal() { +void InitializedMonteCarloParameters::GenerateCircularNormalNormal() { const static int dim = 2; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -166,18 +166,18 @@ void InitMonteCarloParameters::GenerateCircularNormalNormal() { } } -void InitMonteCarloParameters::CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, double theta_min, - double theta_max, double phi_min, double phi_max) { +void InitializedMonteCarloParameters::CalcSphericalNormalUniformUniform(libra::Vector<3>& destination, double r_mean, double r_sigma, + double theta_min, double theta_max, double phi_min, double phi_max) { // r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame - double r = InitMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); - double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); - double phi = InitMonteCarloParameters::Generate1dUniform(phi_min, phi_max); + double r = InitializedMonteCarloParameters::Generate1dNormal(r_mean, r_sigma); + double theta = acos(cos(theta_min) - (cos(theta_min) - cos(theta_max)) * InitializedMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitializedMonteCarloParameters::Generate1dUniform(phi_min, phi_max); destination[0] = r * sin(theta) * cos(phi); destination[1] = r * sin(theta) * sin(phi); destination[2] = r * cos(theta); } -void InitMonteCarloParameters::GenerateSphericalNormalUniformUniform() { +void InitializedMonteCarloParameters::GenerateSphericalNormalUniformUniform() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < dim) { throw "Config parameters dimension unmatched."; @@ -192,7 +192,7 @@ void InitMonteCarloParameters::GenerateSphericalNormalUniformUniform() { } } -void InitMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { +void InitializedMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] libra::Vector<3> mean_vec_dir; mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction @@ -207,23 +207,23 @@ void InitMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3>& desti // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product libra::Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); - double rotation_angle_of_normal_unit_vec = InitMonteCarloParameters::Generate1dUniform(0.0, libra::tau); + double rotation_angle_of_normal_unit_vec = InitializedMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, -rotation_angle_of_normal_unit_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> rotation_axis = rotation_of_normal_unit_vec.FrameConversion(normal_unit_vec); // Axis of mean vector rotation - double rotation_angle_of_mean_vec = InitMonteCarloParameters::Generate1dNormal(0.0, sigma_or_max_[1]); + double rotation_angle_of_mean_vec = InitializedMonteCarloParameters::Generate1dNormal(0.0, sigma_or_max_[1]); libra::Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction - ret_vec = InitMonteCarloParameters::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm + ret_vec = InitializedMonteCarloParameters::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { destination[i] = ret_vec[i]; } } -void InitMonteCarloParameters::GenerateSphericalNormalNormal() { +void InitializedMonteCarloParameters::GenerateSphericalNormalNormal() { const static int dim = 3; if (mean_or_min_.size() < dim || sigma_or_max_.size() < 2) { throw "Config parameters dimension unmatched."; @@ -240,7 +240,7 @@ void InitMonteCarloParameters::GenerateSphericalNormalNormal() { } } -void InitMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destination) { +void InitializedMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destination) { // Perfectly Randomized libra::Quaternion libra::Vector<3> x_axis(0.0); x_axis[0] = 1.0; @@ -248,8 +248,8 @@ void InitMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destinat // A direction vector converted from the X-axis by a quaternion may follows the uniform distribution in full sphere. libra::Quaternion first_cnv; libra::Vector<3> x_axis_cnvd; - double theta = acos(1 - (1 - (-1)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); - double phi = InitMonteCarloParameters::Generate1dUniform(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitializedMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitializedMonteCarloParameters::Generate1dUniform(0, libra::tau); x_axis_cnvd[0] = sin(theta) * cos(phi); x_axis_cnvd[1] = sin(theta) * sin(phi); x_axis_cnvd[2] = cos(theta); @@ -262,7 +262,7 @@ void InitMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destinat first_cnv[3] = cos_angle_between; // Generate randomized rotation angle around the X-axis - double rotation_angle = InitMonteCarloParameters::Generate1dUniform(0.0, libra::tau); + double rotation_angle = InitializedMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion second_cnv(x_axis, rotation_angle); libra::Quaternion ret_q = first_cnv * second_cnv; @@ -272,7 +272,7 @@ void InitMonteCarloParameters::CalcQuaternionUniform(libra::Quaternion& destinat } } -void InitMonteCarloParameters::GenerateQuaternionUniform() { +void InitializedMonteCarloParameters::GenerateQuaternionUniform() { const static int dim = 4; libra::Quaternion temp_q; CalcQuaternionUniform(temp_q); @@ -283,17 +283,17 @@ void InitMonteCarloParameters::GenerateQuaternionUniform() { } } -void InitMonteCarloParameters::CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma) { +void InitializedMonteCarloParameters::CalcQuaternionNormal(libra::Quaternion& destination, double theta_sigma) { // Angle from the default quaternion θ follows normal distribution // The rotation axis follows uniform distribution on full sphere libra::Vector<3> rot_axis; - double theta = acos(1 - (1 - (-1)) * InitMonteCarloParameters::Generate1dUniform(0.0, 1.0)); - double phi = InitMonteCarloParameters::Generate1dUniform(0, libra::tau); + double theta = acos(1 - (1 - (-1)) * InitializedMonteCarloParameters::Generate1dUniform(0.0, 1.0)); + double phi = InitializedMonteCarloParameters::Generate1dUniform(0, libra::tau); rot_axis[0] = sin(theta) * cos(phi); rot_axis[1] = sin(theta) * sin(phi); rot_axis[2] = cos(theta); - double rotation_angle = InitMonteCarloParameters::Generate1dNormal(0.0, theta_sigma); + double rotation_angle = InitializedMonteCarloParameters::Generate1dNormal(0.0, theta_sigma); libra::Quaternion ret_q(rot_axis, rotation_angle); for (int i = 0; i < 4; i++) { @@ -301,7 +301,7 @@ void InitMonteCarloParameters::CalcQuaternionNormal(libra::Quaternion& destinati } } -void InitMonteCarloParameters::GenerateQuaternionNormal() { +void InitializedMonteCarloParameters::GenerateQuaternionNormal() { // mean_or_min_[0]: NA sigma_or_max_[0]: standard deviation of θ [rad] const static int dim = 4; if (sigma_or_max_.size() < 1) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 07bb9d16a..9b4fc13cd 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -14,10 +14,10 @@ #include /** - * @class InitMonteCarloParameters + * @class InitializedMonteCarloParameters * @brief Initialized parameters for Monte-Carlo simulation */ -class InitMonteCarloParameters { +class InitializedMonteCarloParameters { public: /** * @enum RandomizationType @@ -36,10 +36,10 @@ class InitMonteCarloParameters { }; /** - * @fn InitMonteCarloParameters + * @fn InitializedMonteCarloParameters * @brief Constructor */ - InitMonteCarloParameters(); + InitializedMonteCarloParameters(); // Setter /** @@ -205,8 +205,9 @@ class InitMonteCarloParameters { }; template -void InitMonteCarloParameters::SetRandomConfiguration(const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, - InitMonteCarloParameters::RandomizationType random_type) { +void InitializedMonteCarloParameters::SetRandomConfiguration(const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, + InitializedMonteCarloParameters::RandomizationType random_type) { randomization_type_ = random_type; mean_or_min_.clear(); for (size_t i = 0; i < NumElement1; i++) { @@ -219,7 +220,7 @@ void InitMonteCarloParameters::SetRandomConfiguration(const libra::Vector -void InitMonteCarloParameters::GetRandomizedVector(libra::Vector& destination) const { +void InitializedMonteCarloParameters::GetRandomizedVector(libra::Vector& destination) const { if (randomization_type_ == NoRandomization) { ; } else if (NumElement > randomized_value_.size()) { diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 8bf0c7829..32f675074 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -30,7 +30,7 @@ MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { enum Phase { FoundNothingYet, FoundSimulationObjectStr, FoundInitParameterStr }; for (auto so_dot_ip_str : so_dot_ip_str_vec) { - // Divide the string to SimulationObject and InitMonteCarloParameters + // Divide the string to SimulationObject and InitializedMonteCarloParameters Phase phase = FoundNothingYet; std::stringstream ss(so_dot_ip_str); std::string item, so_str, ip_str; @@ -50,32 +50,32 @@ MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { } // Read Randomization type - InitMonteCarloParameters::RandomizationType random_type; + InitializedMonteCarloParameters::RandomizationType random_type; const static unsigned int buf_size = 256; char rnd_type_str[buf_size]; std::string key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "randomization_type"; ini_file.ReadChar(section, key_name.c_str(), buf_size, rnd_type_str); if (!strcmp(rnd_type_str, "NoRandomization")) - random_type = InitMonteCarloParameters::NoRandomization; + random_type = InitializedMonteCarloParameters::NoRandomization; else if (!strcmp(rnd_type_str, "CartesianUniform")) - random_type = InitMonteCarloParameters::CartesianUniform; + random_type = InitializedMonteCarloParameters::CartesianUniform; else if (!strcmp(rnd_type_str, "CartesianNormal")) - random_type = InitMonteCarloParameters::CartesianNormal; + random_type = InitializedMonteCarloParameters::CartesianNormal; else if (!strcmp(rnd_type_str, "CircularNormalUniform")) - random_type = InitMonteCarloParameters::CircularNormalUniform; + random_type = InitializedMonteCarloParameters::CircularNormalUniform; else if (!strcmp(rnd_type_str, "CircularNormalNormal")) - random_type = InitMonteCarloParameters::CircularNormalNormal; + random_type = InitializedMonteCarloParameters::CircularNormalNormal; else if (!strcmp(rnd_type_str, "SphericalNormalUniformUniform")) - random_type = InitMonteCarloParameters::SphericalNormalUniformUniform; + random_type = InitializedMonteCarloParameters::SphericalNormalUniformUniform; else if (!strcmp(rnd_type_str, "SphericalNormalNormal")) - random_type = InitMonteCarloParameters::SphericalNormalNormal; + random_type = InitializedMonteCarloParameters::SphericalNormalNormal; else if (!strcmp(rnd_type_str, "QuaternionUniform")) - random_type = InitMonteCarloParameters::QuaternionUniform; + random_type = InitializedMonteCarloParameters::QuaternionUniform; else if (!strcmp(rnd_type_str, "QuaternionNormal")) - random_type = InitMonteCarloParameters::QuaternionNormal; + random_type = InitializedMonteCarloParameters::QuaternionNormal; else - random_type = InitMonteCarloParameters::NoRandomization; + random_type = InitializedMonteCarloParameters::NoRandomization; // Read mean_or_min vector key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "mean_or_min"; @@ -88,7 +88,7 @@ MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { ini_file.ReadVector(section, key_name.c_str(), sigma_or_max); // Write randomize setting - monte_carlo_simulator->AddInitMonteCarloParameter(so_str, ip_str, mean_or_min, sigma_or_max, random_type); + monte_carlo_simulator->AddInitializedMonteCarloParameter(so_str, ip_str, mean_or_min, sigma_or_max, random_type); } return monte_carlo_simulator; diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp index d4b2d78db..bb736a203 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.cpp @@ -32,8 +32,8 @@ void MonteCarloSimulationExecutor::AtTheEndOfEachCase() { number_of_executions_done_++; } -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_name, string init_monte_carlo_parameter_name, - double& destination) const { +void MonteCarloSimulationExecutor::GetInitializedMonteCarloParameterDouble(string so_name, string init_monte_carlo_parameter_name, + double& destination) const { if (!enabled_) return; { string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; @@ -46,8 +46,8 @@ void MonteCarloSimulationExecutor::GetInitMonteCarloParameterDouble(string so_na } } -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterQuaternion(string so_name, string init_monte_carlo_parameter_name, - libra::Quaternion& destination) const { +void MonteCarloSimulationExecutor::GetInitializedMonteCarloParameterQuaternion(string so_name, string init_monte_carlo_parameter_name, + libra::Quaternion& destination) const { if (!enabled_) return; { string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; @@ -66,4 +66,6 @@ void MonteCarloSimulationExecutor::RandomizeAllParameters() { } } -void MonteCarloSimulationExecutor::SetSeed(unsigned long seed, bool is_deterministic) { InitMonteCarloParameters::SetSeed(seed, is_deterministic); } +void MonteCarloSimulationExecutor::SetSeed(unsigned long seed, bool is_deterministic) { + InitializedMonteCarloParameters::SetSeed(seed, is_deterministic); +} diff --git a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp index 426168a08..83dfcf618 100644 --- a/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp +++ b/src/simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp @@ -23,10 +23,10 @@ class MonteCarloSimulationExecutor { bool enabled_; //!< Flag to execute Monte-Carlo Simulation or not bool save_log_history_flag_; //!< Flag to store the log for each case or not - std::map init_parameter_list_; //!< List of InitMonteCarloParameters read from MCSim.ini + std::map init_parameter_list_; //!< List of InitializedMonteCarloParameters read from MCSim.ini public: - static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitMonteCarloParameters in the initialization file + static const char separator_ = '.'; //!< Deliminator for name of SimulationObject and InitializedMonteCarloParameters in the initialization file /** * @fn MonteCarloSimulationExecutor @@ -81,22 +81,23 @@ class MonteCarloSimulationExecutor { return (!enabled_ || save_log_history_flag_); } /** - * @fn GetInitMonteCarloParameterVector + * @fn GetInitializedMonteCarloParameterVector * @brief Get randomized vector value and store it in dest_vec */ template - void GetInitMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, - libra::Vector& destination) const; + void GetInitializedMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, + libra::Vector& destination) const; /** - * @fn GetInitMonteCarloParameterDouble + * @fn GetInitializedMonteCarloParameterDouble * @brief Get randomized value and store it in dest */ - void GetInitMonteCarloParameterDouble(std::string so_name, std::string init_monte_carlo_parameter_name, double& destination) const; + void GetInitializedMonteCarloParameterDouble(std::string so_name, std::string init_monte_carlo_parameter_name, double& destination) const; /** - * @fn GetInitMonteCarloParameterQuaternion + * @fn GetInitializedMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in dest_quat */ - void GetInitMonteCarloParameterQuaternion(std::string so_name, std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const; + void GetInitializedMonteCarloParameterQuaternion(std::string so_name, std::string init_monte_carlo_parameter_name, + libra::Quaternion& destination) const; // Calculation /** @@ -121,11 +122,12 @@ class MonteCarloSimulationExecutor { template /** - * @fn AddInitMonteCarloParameter + * @fn AddInitializedMonteCarloParameter * @brief Add initialized parameter */ - void AddInitMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, InitMonteCarloParameters::RandomizationType random_type); + void AddInitializedMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, + const libra::Vector& mean_or_min, const libra::Vector& sigma_or_max, + InitializedMonteCarloParameters::RandomizationType random_type); /** * @fn RandomizeAllParameters @@ -135,8 +137,8 @@ class MonteCarloSimulationExecutor { }; template -void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, - libra::Vector& destination) const { +void MonteCarloSimulationExecutor::GetInitializedMonteCarloParameterVector(std::string so_name, std::string init_monte_carlo_parameter_name, + libra::Vector& destination) const { if (!enabled_) return; std::string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { @@ -148,19 +150,19 @@ void MonteCarloSimulationExecutor::GetInitMonteCarloParameterVector(std::string } template -void MonteCarloSimulationExecutor::AddInitMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, - const libra::Vector& mean_or_min, - const libra::Vector& sigma_or_max, - InitMonteCarloParameters::RandomizationType random_type) { +void MonteCarloSimulationExecutor::AddInitializedMonteCarloParameter(std::string so_name, std::string init_monte_carlo_parameter_name, + const libra::Vector& mean_or_min, + const libra::Vector& sigma_or_max, + InitializedMonteCarloParameters::RandomizationType random_type) { std::string name = so_name + MonteCarloSimulationExecutor::separator_ + init_monte_carlo_parameter_name; if (init_parameter_list_.find(name) == init_parameter_list_.end()) { // Register the parameter in ip_list if it is not registered yet - auto newparam = new InitMonteCarloParameters(); + auto newparam = new InitializedMonteCarloParameters(); newparam->SetRandomConfiguration(mean_or_min, sigma_or_max, random_type); init_parameter_list_[name] = newparam; } else { // Throw error if the parameter is already registered - throw "More than one definition of one InitMonteCarloParameters."; + throw "More than one definition of one InitializedMonteCarloParameters."; } } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index b5cb96a91..0fc796262 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -32,12 +32,13 @@ void SimulationObject::SetAllParameters(const MonteCarloSimulationExecutor& mont } } -void SimulationObject::GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, - std::string init_monte_carlo_parameter_name, double& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterDouble(name_, init_monte_carlo_parameter_name, destination); +void SimulationObject::GetInitializedMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, double& destination) const { + monte_carlo_simulator.GetInitializedMonteCarloParameterDouble(name_, init_monte_carlo_parameter_name, destination); } -void SimulationObject::GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, - std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterQuaternion(name_, init_monte_carlo_parameter_name, destination); +void SimulationObject::GetInitializedMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, + libra::Quaternion& destination) const { + monte_carlo_simulator.GetInitializedMonteCarloParameterQuaternion(name_, init_monte_carlo_parameter_name, destination); } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index bc77a4d8a..87afe112b 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -35,26 +35,26 @@ class SimulationObject { virtual ~SimulationObject(); /** - * @fn GetInitMonteCarloParameterVector + * @fn GetInitializedMonteCarloParameterVector * @brief Get randomized vector value and store it in destination */ template - void GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, - libra::Vector& destination) const; + void GetInitializedMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, + libra::Vector& destination) const; /** - * @fn GetInitMonteCarloParameterDouble + * @fn GetInitializedMonteCarloParameterDouble * @brief Get randomized value and store it in destination */ - void GetInitMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, - double& destination) const; + void GetInitializedMonteCarloParameterDouble(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, + double& destination) const; /** - * @fn GetInitMonteCarloParameterQuaternion + * @fn GetInitializedMonteCarloParameterQuaternion * @brief Get randomized quaternion and store it in destination */ - void GetInitMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string init_monte_carlo_parameter_name, - libra::Quaternion& destination) const; + void GetInitializedMonteCarloParameterQuaternion(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, libra::Quaternion& destination) const; /** * @fn SetParameters @@ -74,13 +74,14 @@ class SimulationObject { }; /** - * @fn GetInitMonteCarloParameterVector + * @fn GetInitializedMonteCarloParameterVector * @brief Return initialized parameters for vector */ template -void SimulationObject::GetInitMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, - std::string init_monte_carlo_parameter_name, libra::Vector& destination) const { - monte_carlo_simulator.GetInitMonteCarloParameterVector(name_, init_monte_carlo_parameter_name, destination); +void SimulationObject::GetInitializedMonteCarloParameterVector(const MonteCarloSimulationExecutor& monte_carlo_simulator, + std::string init_monte_carlo_parameter_name, + libra::Vector& destination) const { + monte_carlo_simulator.GetInitializedMonteCarloParameterVector(name_, init_monte_carlo_parameter_name, destination); } #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_SIMULATION_OBJECT_HPP_ From 651a39f00c22b9c13c72b5b023a1640af58da991 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:27:30 +0100 Subject: [PATCH 0921/1086] Fix function argument names --- src/simulation/hils/hils_port_manager.cpp | 55 ++++++++++++----------- src/simulation/hils/hils_port_manager.hpp | 27 +++++------ 2 files changed, 42 insertions(+), 40 deletions(-) diff --git a/src/simulation/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp index a70902bcb..b794334be 100644 --- a/src/simulation/hils/hils_port_manager.cpp +++ b/src/simulation/hils/hils_port_manager.cpp @@ -16,7 +16,7 @@ HilsPortManager::~HilsPortManager() {} // UART Communication port functions int HilsPortManager::UartConnectComPort(unsigned int port_id, unsigned int baud_rate, unsigned int tx_buffer_size, unsigned int rx_buffer_size) { #ifdef USE_HILS - if (uart_com_ports_[port_id] != nullptr) { + if (uart_ports_[port_id] != nullptr) { printf("Error: Port is already used\n"); return -1; } @@ -24,7 +24,7 @@ int HilsPortManager::UartConnectComPort(unsigned int port_id, unsigned int baud_ printf("Error: Illegal parameter\n"); return -1; } - uart_com_ports_[port_id] = new HilsUartPort(port_id, baud_rate, tx_buffer_size, rx_buffer_size); + uart_ports_[port_id] = new HilsUartPort(port_id, baud_rate, tx_buffer_size, rx_buffer_size); return 0; #else UNUSED(port_id); @@ -39,15 +39,15 @@ int HilsPortManager::UartConnectComPort(unsigned int port_id, unsigned int baud_ // Close port and free resources int HilsPortManager::UartCloseComPort(unsigned int port_id) { #ifdef USE_HILS - if (uart_com_ports_[port_id] == nullptr) { + if (uart_ports_[port_id] == nullptr) { // Port not used return -1; } - uart_com_ports_[port_id]->ClosePort(); - HilsUartPort* port = uart_com_ports_.at(port_id); + uart_ports_[port_id]->ClosePort(); + HilsUartPort* port = uart_ports_.at(port_id); delete port; - uart_com_ports_.erase(port_id); + uart_ports_.erase(port_id); return 0; #else UNUSED(port_id); @@ -56,11 +56,11 @@ int HilsPortManager::UartCloseComPort(unsigned int port_id) { #endif } -int HilsPortManager::UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int count) { +int HilsPortManager::UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int length) { #ifdef USE_HILS - HilsUartPort* port = uart_com_ports_[port_id]; + HilsUartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - int ret = port->ReadRx(buffer, offset, count); + int ret = port->ReadRx(buffer, offset, length); #ifdef HILS_PORT_MANAGER_SHOW_DEBUG_DATA if (ret > 0) { printf("UART PORT ID: %d received %d bytes\n", port_id, ret); @@ -75,21 +75,21 @@ int HilsPortManager::UartReceive(unsigned int port_id, unsigned char* buffer, in UNUSED(port_id); UNUSED(buffer); UNUSED(offset); - UNUSED(count); + UNUSED(length); return -1; #endif } -int HilsPortManager::UartSend(unsigned int port_id, const unsigned char* buffer, int offset, int count) { +int HilsPortManager::UartSend(unsigned int port_id, const unsigned char* buffer, int offset, int length) { #ifdef USE_HILS - HilsUartPort* port = uart_com_ports_[port_id]; + HilsUartPort* port = uart_ports_[port_id]; if (port == nullptr) return -1; - int ret = port->WriteTx(buffer, offset, count); + int ret = port->WriteTx(buffer, offset, length); #ifdef HILS_PORT_MANAGER_SHOW_DEBUG_DATA - if (count > 0) { - printf("UART PORT ID: %d sent %d bytes\n", port_id, count); - for (int i = 0; i < count; i++) { + if (length > 0) { + printf("UART PORT ID: %d sent %d bytes\n", port_id, length); + for (int i = 0; i < length; i++) { printf("%02x ", buffer[i]); } printf("\n"); @@ -100,7 +100,7 @@ int HilsPortManager::UartSend(unsigned int port_id, const unsigned char* buffer, UNUSED(port_id); UNUSED(buffer); UNUSED(offset); - UNUSED(count); + UNUSED(length); return -1; #endif @@ -141,18 +141,18 @@ int HilsPortManager::I2cTargetCloseComPort(unsigned int port_id) { #endif } -int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, +int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char register_address, const unsigned char* data, const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < length; i++) { - port->WriteRegister(reg_address + i, data[i]); + port->WriteRegister(register_address + i, data[i]); } return 0; #else UNUSED(port_id); - UNUSED(reg_address); + UNUSED(register_address); UNUSED(data); UNUSED(length); @@ -160,17 +160,18 @@ int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned #endif } -int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length) { +int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char register_address, unsigned char* data, + const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < length; i++) { - data[i] = port->ReadRegister(reg_address + i); + data[i] = port->ReadRegister(register_address + i); } return 0; #else UNUSED(port_id); - UNUSED(reg_address); + UNUSED(register_address); UNUSED(data); UNUSED(length); @@ -250,10 +251,10 @@ int HilsPortManager::I2cControllerConnectComPort(unsigned int port_id, unsigned int HilsPortManager::I2cControllerCloseComPort(unsigned int port_id) { return UartCloseComPort(port_id); } -int HilsPortManager::I2cControllerReceive(unsigned int port_id, unsigned char* buffer, int offset, int count) { - return UartReceive(port_id, buffer, offset, count); +int HilsPortManager::I2cControllerReceive(unsigned int port_id, unsigned char* buffer, int offset, int length) { + return UartReceive(port_id, buffer, offset, length); } -int HilsPortManager::I2cControllerSend(unsigned int port_id, const unsigned char* buffer, int offset, int count) { - return UartSend(port_id, buffer, offset, count); +int HilsPortManager::I2cControllerSend(unsigned int port_id, const unsigned char* buffer, int offset, int length) { + return UartSend(port_id, buffer, offset, length); } diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index ebbade3b9..be616e79b 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -51,18 +51,18 @@ class HilsPortManager { * @param [in] port_id: COM port ID * @param [out] buffer: Data buffer to receive * @param [in] offset: Start offset for the data buffer to receive - * @param [in] count: Length of data to receive + * @param [in] length: Length of data to receive */ - virtual int UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int count); + virtual int UartReceive(unsigned int port_id, unsigned char* buffer, int offset, int length); /** * @fn UartSend * @brief UART data send from components in S2E to COM port (ex. OBC) * @param [in] port_id: COM port ID * @param [in] buffer: Data buffer to send * @param [in] offset: Start offset for the data buffer to send - * @param [in] count: Length of data to send + * @param [in] length: Length of data to send */ - virtual int UartSend(unsigned int port_id, const unsigned char* buffer, int offset, int count); + virtual int UartSend(unsigned int port_id, const unsigned char* buffer, int offset, int length); // I2C Target Communication port functions /** @@ -81,20 +81,21 @@ class HilsPortManager { * @fn I2cTargetReadRegister * @brief Read I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_address: Register address to read + * @param [in] register_address: Register address to read * @param [out] data: Data buffer to store the read data * @param [in] length: Read data length */ - virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length); + virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char register_address, unsigned char* data, const unsigned char length); /** * @fn I2cTargetWriteRegister * @brief Write data to I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_address: Register address to write + * @param [in] register_address: Register address to write * @param [in] data: Data to write * @param [in] length: Write data length */ - virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, const unsigned char length); + virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char register_address, const unsigned char* data, + const unsigned char length); /** * @fn I2cTargetReadCommand * @brief Read I2C command buffer in S2E @@ -147,22 +148,22 @@ class HilsPortManager { * @param [in] port_id: COM port ID * @param [out] buffer: Data buffer to receive * @param [in] offset: Start offset for the data buffer to receive - * @param [in] count: Length of data to receive + * @param [in] length: Length of data to receive */ - virtual int I2cControllerReceive(unsigned int port_id, unsigned char* buffer, int offset, int count); + virtual int I2cControllerReceive(unsigned int port_id, unsigned char* buffer, int offset, int length); /** * @fn I2cControllerSend * @brief Data send to I2C controller device connected a COM port * @param [in] port_id: COM port ID * @param [in] buffer: Data buffer to send * @param [in] offset: Start offset for the data buffer to send - * @param [in] count: Length of data to send + * @param [in] length: Length of data to send */ - virtual int I2cControllerSend(unsigned int port_id, const unsigned char* buffer, int offset, int count); + virtual int I2cControllerSend(unsigned int port_id, const unsigned char* buffer, int offset, int length); private: #ifdef USE_HILS - std::map uart_com_ports_; //!< UART ports + std::map uart_ports_; //!< UART ports std::map i2c_ports_; //!< I2C ports #endif }; From 0cc51a00b443f497033327d5ce4d19162f33c4ab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:35:14 +0100 Subject: [PATCH 0922/1086] Fix public function name --- .../ground_station_calculator.cpp | 6 +-- src/simulation/case/sample_case.cpp | 4 +- .../ground_station/ground_station.cpp | 34 +++++++------- .../ground_station/ground_station.hpp | 44 +++++++++---------- .../sample_ground_station.cpp | 8 ++-- .../sample_ground_station.hpp | 4 +- 6 files changed, 51 insertions(+), 49 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index f2a0a321b..e21058fd8 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -68,7 +68,7 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); - Vector<3> gs_pos_i = ground_station.GetGSPosition_i(); + Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_tx_antenna.GetFrequency_MHz() / 1000.0)); @@ -81,9 +81,9 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante double phi_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_antenna_rad)); // SC direction on GS RX antenna frame - Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetGSPosition_ecef(); + Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetPosition_ecef_m(); gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); - Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGSPosition_geo().GetQuaternionXcxfToLtc(); + Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 152020b85..49bd897f5 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -19,8 +19,8 @@ void SampleCase::Initialize() { // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini const int spacecraft_id = 0; sample_sat_ = new SampleSat(&sim_config_, global_environment_, spacecraft_id); - const int gs_id = 0; - sample_gs_ = new SampleGS(&sim_config_, gs_id); + const int ground_station_id = 0; + sample_gs_ = new SampleGS(&sim_config_, ground_station_id); // Register the log output global_environment_->LogSetup(*(sim_config_.main_logger_)); diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index c074fae87..1530b2013 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -13,29 +13,29 @@ #include #include -GroundStation::GroundStation(SimulationConfig* configuration, int gs_id) : gs_id_(gs_id) { - Initialize(gs_id_, configuration); - num_sc_ = configuration->number_of_simulated_spacecraft_; - for (int i = 0; i < num_sc_; i++) { +GroundStation::GroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id) : ground_station_id_(ground_station_id) { + Initialize(configuration, ground_station_id_); + number_of_spacecraft_ = configuration->number_of_simulated_spacecraft_; + for (unsigned int i = 0; i < number_of_spacecraft_; i++) { is_visible_[i] = false; } } GroundStation::~GroundStation() {} -void GroundStation::Initialize(int gs_id, SimulationConfig* configuration) { +void GroundStation::Initialize(const SimulationConfig* configuration, const unsigned int ground_station_id) { std::string gs_ini_path = configuration->ground_station_file_list_[0]; auto conf = IniAccess(gs_ini_path); const char* section_base = "GROUND_STATION_"; - const std::string section_tmp = section_base + std::to_string(static_cast(gs_id)); + const std::string section_tmp = section_base + std::to_string(static_cast(ground_station_id)); const char* Section = section_tmp.data(); double latitude_deg = conf.ReadDouble(Section, "latitude_deg"); double longitude_deg = conf.ReadDouble(Section, "longitude_deg"); double height_m = conf.ReadDouble(Section, "height_m"); - gs_position_geo_ = GeodeticPosition(latitude_deg * libra::deg_to_rad, longitude_deg * libra::deg_to_rad, height_m); - gs_position_ecef_ = gs_position_geo_.CalcEcefPosition(); + geodetic_position_ = GeodeticPosition(latitude_deg * libra::deg_to_rad, longitude_deg * libra::deg_to_rad, height_m); + position_ecef_m_ = geodetic_position_.CalcEcefPosition(); elevation_limit_angle_deg_ = conf.ReadDouble(Section, "elevation_limit_angle_deg"); @@ -44,17 +44,17 @@ void GroundStation::Initialize(int gs_id, SimulationConfig* configuration) { void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } -void GroundStation::Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft) { - libra::Matrix<3, 3> dcm_ecef2eci = Transpose(celes_rotation.GetDcmJ2000ToXcxf()); - gs_position_i_ = dcm_ecef2eci * gs_position_ecef_; +void GroundStation::Update(const CelestialRotation& celestial_rotation, const Spacecraft& spacecraft) { + libra::Matrix<3, 3> dcm_ecef2eci = Transpose(celestial_rotation.GetDcmJ2000ToXcxf()); + position_i_m_ = dcm_ecef2eci * position_ecef_m_; is_visible_[spacecraft.GetSpacecraftId()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); } -bool GroundStation::CalcIsVisible(const libra::Vector<3> sc_pos_ecef_m) { - libra::Quaternion q_ecef_to_ltc = gs_position_geo_.GetQuaternionXcxfToLtc(); +bool GroundStation::CalcIsVisible(const libra::Vector<3> spacecraft_position_ecef_m) { + libra::Quaternion q_ecef_to_ltc = geodetic_position_.GetQuaternionXcxfToLtc(); - libra::Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(sc_pos_ecef_m - gs_position_ecef_); // Satellite position in LTC frame [m] + libra::Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(spacecraft_position_ecef_m - position_ecef_m_); // Satellite position in LTC frame [m] Normalize(sc_pos_ltc); libra::Vector<3> dir_gs_to_zenith = libra::Vector<3>(0); dir_gs_to_zenith[2] = 1; @@ -71,8 +71,8 @@ bool GroundStation::CalcIsVisible(const libra::Vector<3> sc_pos_ecef_m) { std::string GroundStation::GetLogHeader() const { std::string str_tmp = ""; - std::string head = "ground_station" + std::to_string(gs_id_) + "_"; - for (int i = 0; i < num_sc_; i++) { + std::string head = "ground_station" + std::to_string(ground_station_id_) + "_"; + for (unsigned int i = 0; i < number_of_spacecraft_; i++) { std::string legend = head + "sc" + std::to_string(i) + "_visible_flag"; str_tmp += WriteScalar(legend); } @@ -82,7 +82,7 @@ std::string GroundStation::GetLogHeader() const { std::string GroundStation::GetLogValue() const { std::string str_tmp = ""; - for (int i = 0; i < num_sc_; i++) { + for (unsigned int i = 0; i < number_of_spacecraft_; i++) { str_tmp += WriteScalar(is_visible_.at(i)); } return str_tmp; diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 59fac8be7..3c1b06395 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -23,7 +23,7 @@ class GroundStation : public ILoggable { * @fn GroundStation * @brief Constructor */ - GroundStation(SimulationConfig* configuration, int gs_id_); + GroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id_); /** * @fn ~GroundStation * @brief Destructor @@ -34,7 +34,7 @@ class GroundStation : public ILoggable { * @fn Initialize * @brief Virtual function to initialize the ground station */ - virtual void Initialize(int gs_id, SimulationConfig* configuration); + virtual void Initialize(const SimulationConfig* configuration, const unsigned int ground_station_id); /** * @fn LogSetup * @brief Virtual function to log output setting for ground station related components @@ -44,7 +44,7 @@ class GroundStation : public ILoggable { * @fn Update * @brief Virtual function of main routine */ - virtual void Update(const CelestialRotation& celes_rotation, const Spacecraft& spacecraft); + virtual void Update(const CelestialRotation& celestial_rotation, const Spacecraft& spacecraft); // Override functions for ILoggable /** @@ -60,25 +60,25 @@ class GroundStation : public ILoggable { // Getters /** - * @fn GetGsId + * @fn GetGroundStationId * @brief Return ground station ID */ - int GetGsId() const { return gs_id_; } + int GetGroundStationId() const { return ground_station_id_; } /** - * @fn GetGSPosition_geo + * @fn GetGeodeticPosition * @brief Return ground station position in the geodetic frame */ - GeodeticPosition GetGSPosition_geo() const { return gs_position_geo_; } + GeodeticPosition GetGeodeticPosition() const { return geodetic_position_; } /** - * @fn GetGSPosition_ecef + * @fn GetPosition_ecef_m * @brief Return ground station position in the ECEF frame [m] */ - Vector<3> GetGSPosition_ecef() const { return gs_position_ecef_; } + Vector<3> GetPosition_ecef_m() const { return position_ecef_m_; } /** - * @fn GetGSPosition_i + * @fn GetPosition_i_m * @brief Return ground station position in the inertial frame [m] */ - Vector<3> GetGSPosition_i() const { return gs_position_i_; } + Vector<3> GetPosition_i_m() const { return position_i_m_; } /** * @fn GetElevationLimitAngle_deg * @brief Return ground station elevation limit angle [deg] @@ -87,27 +87,27 @@ class GroundStation : public ILoggable { /** * @fn IsVisible * @brief Return visible flag for the target spacecraft - * @param [in] sc_id: target spacecraft ID + * @param [in] spacecraft_id: target spacecraft ID */ - bool IsVisible(const int sc_id) const { return is_visible_.at(sc_id); } + bool IsVisible(const unsigned int spacecraft_id) const { return is_visible_.at(spacecraft_id); } protected: - int gs_id_; //!< Ground station ID - GeodeticPosition gs_position_geo_; //!< Ground Station Position in the geodetic frame - Vector<3> gs_position_ecef_; //!< Ground Station Position in the ECEF frame [m] - Vector<3> gs_position_i_; //!< Ground Station Position in the inertial frame [m] - double elevation_limit_angle_deg_; //!< Minimum elevation angle to work the ground station [deg] + unsigned int ground_station_id_; //!< Ground station ID + GeodeticPosition geodetic_position_; //!< Ground Station Position in the geodetic frame + Vector<3> position_ecef_m_; //!< Ground Station Position in the ECEF frame [m] + Vector<3> position_i_m_; //!< Ground Station Position in the inertial frame [m] + double elevation_limit_angle_deg_; //!< Minimum elevation angle to work the ground station [deg] - std::map is_visible_; //!< Visible flag for each spacecraft ID (not care antenna) - int num_sc_; //!< Number of spacecraft in the simulation + std::map is_visible_; //!< Visible flag for each spacecraft ID (not care antenna) + unsigned int number_of_spacecraft_; //!< Number of spacecraft in the simulation /** * @fn CalcIsVisible * @brief Calculate the visibility for the target spacecraft - * @param [in] sc_pos_ecef_m: spacecraft position in ECEF frame [m] + * @param [in] spacecraft_position_ecef_m: spacecraft position in ECEF frame [m] * @return True when the satellite is visible from the ground station */ - bool CalcIsVisible(const Vector<3> sc_pos_ecef_m); + bool CalcIsVisible(const Vector<3> spacecraft_position_ecef_m); }; #endif // S2E_SIMULATION_GROUND_STATION_GROUND_STATION_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index ba852912d..baa090e7e 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -7,7 +7,9 @@ #include "sample_ground_station_components.hpp" -SampleGS::SampleGS(SimulationConfig* configuration, int gs_id) : GroundStation(configuration, gs_id) { Initialize(configuration); } +SampleGS::SampleGS(SimulationConfig* configuration, int ground_station_id) : GroundStation(configuration, ground_station_id) { + Initialize(configuration); +} SampleGS::~SampleGS() { delete components_; } @@ -18,7 +20,7 @@ void SampleGS::LogSetup(Logger& logger) { components_->CompoLogSetUp(logger); } -void SampleGS::Update(const CelestialRotation& celes_rotation, const SampleSat& spacecraft) { - GroundStation::Update(celes_rotation, spacecraft); +void SampleGS::Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft) { + GroundStation::Update(celestial_rotation, spacecraft); components_->GetGsCalculator()->Update(spacecraft, spacecraft.GetInstalledComponents().GetAntenna(), *this, *(components_->GetAntenna())); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index d84c40d6d..2219ce6f9 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -26,7 +26,7 @@ class SampleGS : public GroundStation { * @fn SampleGS * @brief Constructor */ - SampleGS(SimulationConfig* configuration, int gs_id); + SampleGS(SimulationConfig* configuration, int ground_station_id); /** * @fn ~SampleGS * @brief Destructor @@ -47,7 +47,7 @@ class SampleGS : public GroundStation { * @fn Update * @brief Override function of Update in GroundStation class */ - virtual void Update(const CelestialRotation& celes_rotation, const SampleSat& spacecraft); + virtual void Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft); private: SampleGSComponents* components_; //!< Ground station related components From fa4ce35a1a64da94441ecb35e61f87adbfda08fb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:36:52 +0100 Subject: [PATCH 0923/1086] Rename class --- .../sample_ground_station/sample_ground_station.cpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 4 ++-- .../sample_ground_station_components.cpp | 12 ++++++------ .../sample_ground_station_components.hpp | 12 ++++++------ 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index baa090e7e..99d0db783 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -13,7 +13,7 @@ SampleGS::SampleGS(SimulationConfig* configuration, int ground_station_id) : Gro SampleGS::~SampleGS() { delete components_; } -void SampleGS::Initialize(SimulationConfig* configuration) { components_ = new SampleGSComponents(configuration); } +void SampleGS::Initialize(SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } void SampleGS::LogSetup(Logger& logger) { GroundStation::LogSetup(logger); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 2219ce6f9..44f4417a1 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -14,7 +14,7 @@ #include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" #include "../ground_station.hpp" -class SampleGSComponents; +class SampleGsComponents; /** * @class SampleGS @@ -50,7 +50,7 @@ class SampleGS : public GroundStation { virtual void Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft); private: - SampleGSComponents* components_; //!< Ground station related components + SampleGsComponents* components_; //!< Ground station related components }; #endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index 287d500a6..f9ce949c7 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -6,23 +6,23 @@ #include -SampleGSComponents::SampleGSComponents(const SimulationConfig* configuration) : configuration_(configuration) { +SampleGsComponents::SampleGsComponents(const SimulationConfig* configuration) : configuration_(configuration) { IniAccess iniAccess = IniAccess(configuration_->ground_station_file_list_[0]); std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); configuration_->main_logger_->CopyFileToLogDirectory(ant_ini_path); antenna_ = new Antenna(InitAntenna(1, ant_ini_path)); - std::string gscalculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); - configuration_->main_logger_->CopyFileToLogDirectory(gscalculator_ini_path); - gs_calculator_ = new GroundStationCalculator(InitGsCalculator(gscalculator_ini_path)); + std::string gs_calculator_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_calculator_file"); + configuration_->main_logger_->CopyFileToLogDirectory(gs_calculator_ini_path); + gs_calculator_ = new GroundStationCalculator(InitGsCalculator(gs_calculator_ini_path)); } -SampleGSComponents::~SampleGSComponents() { +SampleGsComponents::~SampleGsComponents() { delete antenna_; delete gs_calculator_; } -void SampleGSComponents::CompoLogSetUp(Logger& logger) { +void SampleGsComponents::CompoLogSetUp(Logger& logger) { // logger.AddLogList(ant_); logger.AddLogList(gs_calculator_); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 8954e41dd..6cc30d558 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -10,21 +10,21 @@ #include /** - * @class SampleGSComponents + * @class SampleGsComponents * @brief An example of ground station related components list class */ -class SampleGSComponents { +class SampleGsComponents { public: /** - * @fn SampleGSComponents + * @fn SampleGsComponents * @brief Constructor */ - SampleGSComponents(const SimulationConfig* configuration); + SampleGsComponents(const SimulationConfig* configuration); /** - * @fn ~SampleGSComponents + * @fn ~SampleGsComponents * @brief Destructor */ - ~SampleGSComponents(); + ~SampleGsComponents(); /** * @fn CompoLogSetUp * @brief Log setup for ground station components From b6b1093e1ebcb9ecda359a6606dfd82459b5ae34 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:37:45 +0100 Subject: [PATCH 0924/1086] Fix function argument name --- .../sample_ground_station/sample_ground_station.cpp | 4 ++-- .../sample_ground_station/sample_ground_station.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index 99d0db783..9c080facd 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -7,13 +7,13 @@ #include "sample_ground_station_components.hpp" -SampleGS::SampleGS(SimulationConfig* configuration, int ground_station_id) : GroundStation(configuration, ground_station_id) { +SampleGS::SampleGS(const SimulationConfig* configuration, const unsigned int ground_station_id) : GroundStation(configuration, ground_station_id) { Initialize(configuration); } SampleGS::~SampleGS() { delete components_; } -void SampleGS::Initialize(SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } +void SampleGS::Initialize(const SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } void SampleGS::LogSetup(Logger& logger) { GroundStation::LogSetup(logger); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 44f4417a1..a087b6d97 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -26,7 +26,7 @@ class SampleGS : public GroundStation { * @fn SampleGS * @brief Constructor */ - SampleGS(SimulationConfig* configuration, int ground_station_id); + SampleGS(const SimulationConfig* configuration, const unsigned int ground_station_id); /** * @fn ~SampleGS * @brief Destructor @@ -37,7 +37,7 @@ class SampleGS : public GroundStation { * @fn Initialize * @brief Override function of Initialize in GroundStation class */ - virtual void Initialize(SimulationConfig* configuration); + virtual void Initialize(const SimulationConfig* configuration); /** * @fn LogSetup * @brief Override function of LogSetup in GroundStation class From bc442ab5f1a9d81bc353d52579bafa36167a6c57 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:38:11 +0100 Subject: [PATCH 0925/1086] Rename class --- src/simulation/case/sample_case.cpp | 2 +- src/simulation/case/sample_case.hpp | 4 ++-- .../sample_ground_station/sample_ground_station.cpp | 11 ++++++----- .../sample_ground_station/sample_ground_station.hpp | 12 ++++++------ 4 files changed, 15 insertions(+), 14 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 49bd897f5..1d824399f 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -20,7 +20,7 @@ void SampleCase::Initialize() { const int spacecraft_id = 0; sample_sat_ = new SampleSat(&sim_config_, global_environment_, spacecraft_id); const int ground_station_id = 0; - sample_gs_ = new SampleGS(&sim_config_, ground_station_id); + sample_gs_ = new SampleGroundStation(&sim_config_, ground_station_id); // Register the log output global_environment_->LogSetup(*(sim_config_.main_logger_)); diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 373a79ba0..4f212ac4c 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -52,8 +52,8 @@ class SampleCase : public SimulationCase { virtual std::string GetLogValue() const; private: - SampleSat* sample_sat_; //!< Instance of spacecraft - SampleGS* sample_gs_; //!< Instance of ground station + SampleSat* sample_sat_; //!< Instance of spacecraft + SampleGroundStation* sample_gs_; //!< Instance of ground station }; #endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index 9c080facd..205e30fea 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -7,20 +7,21 @@ #include "sample_ground_station_components.hpp" -SampleGS::SampleGS(const SimulationConfig* configuration, const unsigned int ground_station_id) : GroundStation(configuration, ground_station_id) { +SampleGroundStation::SampleGroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id) + : GroundStation(configuration, ground_station_id) { Initialize(configuration); } -SampleGS::~SampleGS() { delete components_; } +SampleGroundStation::~SampleGroundStation() { delete components_; } -void SampleGS::Initialize(const SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } +void SampleGroundStation::Initialize(const SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } -void SampleGS::LogSetup(Logger& logger) { +void SampleGroundStation::LogSetup(Logger& logger) { GroundStation::LogSetup(logger); components_->CompoLogSetUp(logger); } -void SampleGS::Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft) { +void SampleGroundStation::Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft) { GroundStation::Update(celestial_rotation, spacecraft); components_->GetGsCalculator()->Update(spacecraft, spacecraft.GetInstalledComponents().GetAntenna(), *this, *(components_->GetAntenna())); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index a087b6d97..1d4a48c85 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -17,21 +17,21 @@ class SampleGsComponents; /** - * @class SampleGS + * @class SampleGroundStation * @brief An example of user defined ground station class */ -class SampleGS : public GroundStation { +class SampleGroundStation : public GroundStation { public: /** - * @fn SampleGS + * @fn SampleGroundStation * @brief Constructor */ - SampleGS(const SimulationConfig* configuration, const unsigned int ground_station_id); + SampleGroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id); /** - * @fn ~SampleGS + * @fn ~SampleGroundStation * @brief Destructor */ - ~SampleGS(); + ~SampleGroundStation(); /** * @fn Initialize From 6c04e1c522efad05ddfe5fa1a16c6abe01f55532 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:41:36 +0100 Subject: [PATCH 0926/1086] Fix simulation case --- src/simulation/case/sample_case.cpp | 16 ++++----- src/simulation/case/sample_case.hpp | 2 +- src/simulation/case/simulation_case.cpp | 48 +++++++++++++------------ src/simulation/case/simulation_case.hpp | 12 +++---- 4 files changed, 41 insertions(+), 37 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 1d824399f..9a9ca1213 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -10,7 +10,7 @@ using std::cout; using std::string; -SampleCase::SampleCase(string ini_base) : SimulationCase(ini_base) {} +SampleCase::SampleCase(string initialise_base_file) : SimulationCase(initialise_base_file) {} SampleCase::~SampleCase() { delete sample_sat_; } @@ -18,17 +18,17 @@ void SampleCase::Initialize() { // Instantiate the target of the simulation // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini const int spacecraft_id = 0; - sample_sat_ = new SampleSat(&sim_config_, global_environment_, spacecraft_id); + sample_sat_ = new SampleSat(&simulation_configuration_, global_environment_, spacecraft_id); const int ground_station_id = 0; - sample_gs_ = new SampleGroundStation(&sim_config_, ground_station_id); + sample_gs_ = new SampleGroundStation(&simulation_configuration_, ground_station_id); // Register the log output - global_environment_->LogSetup(*(sim_config_.main_logger_)); - sample_sat_->LogSetup(*(sim_config_.main_logger_)); - sample_gs_->LogSetup(*(sim_config_.main_logger_)); + global_environment_->LogSetup(*(simulation_configuration_.main_logger_)); + sample_sat_->LogSetup(*(simulation_configuration_.main_logger_)); + sample_gs_->LogSetup(*(simulation_configuration_.main_logger_)); // Write headers to the log - sim_config_.main_logger_->WriteHeaders(); + simulation_configuration_.main_logger_->WriteHeaders(); // Start the simulation cout << "\nSimulationDateTime \n"; @@ -40,7 +40,7 @@ void SampleCase::Main() { while (!global_environment_->GetSimulationTime().GetState().finish) { // Logging if (global_environment_->GetSimulationTime().GetState().log_output) { - sim_config_.main_logger_->WriteValues(); + simulation_configuration_.main_logger_->WriteValues(); } // Global Environment Update diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 4f212ac4c..43142ea25 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -20,7 +20,7 @@ class SampleCase : public SimulationCase { * @fn SampleCase * @brief Constructor */ - SampleCase(std::string ini_base); + SampleCase(std::string initialise_base_file); /** * @fn ~SampleCase diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 38000a1ae..2de83349b 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -9,38 +9,42 @@ #include #include -SimulationCase::SimulationCase(std::string ini_base) { - IniAccess simbase_ini = IniAccess(ini_base); +SimulationCase::SimulationCase(const std::string initialise_base_file) { + IniAccess simbase_ini = IniAccess(initialise_base_file); const char* section = "SIMULATION_SETTINGS"; - sim_config_.initialize_base_file_name_ = ini_base; - sim_config_.main_logger_ = InitLog(sim_config_.initialize_base_file_name_); - sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + simulation_configuration_.initialize_base_file_name_ = initialise_base_file; + simulation_configuration_.main_logger_ = InitLog(simulation_configuration_.initialize_base_file_name_); + simulation_configuration_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); + simulation_configuration_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); - sim_config_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); - sim_config_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + simulation_configuration_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); + simulation_configuration_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); - sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); - sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); - global_environment_ = new GlobalEnvironment(&sim_config_); + simulation_configuration_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); + simulation_configuration_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); + global_environment_ = new GlobalEnvironment(&simulation_configuration_); } -SimulationCase::SimulationCase(std::string ini_base, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { - IniAccess simbase_ini = IniAccess(ini_base); + +SimulationCase::SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, + const std::string log_path) { + IniAccess simbase_ini = IniAccess(initialise_base_file); const char* section = "SIMULATION_SETTINGS"; - sim_config_.initialize_base_file_name_ = ini_base; + simulation_configuration_.initialize_base_file_name_ = initialise_base_file; // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; // ToDo: Consider that `enable_inilog = false` is fine or not? - sim_config_.main_logger_ = new Logger(log_file_name, log_path, ini_base, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); - sim_config_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - sim_config_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + simulation_configuration_.main_logger_ = + new Logger(log_file_name, log_path, initialise_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); + simulation_configuration_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); + simulation_configuration_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); - sim_config_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); - sim_config_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + simulation_configuration_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); + simulation_configuration_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); - sim_config_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); - sim_config_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); + simulation_configuration_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); + simulation_configuration_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); // Global Environment - global_environment_ = new GlobalEnvironment(&sim_config_); + global_environment_ = new GlobalEnvironment(&simulation_configuration_); } + SimulationCase::~SimulationCase() { delete global_environment_; } diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 0388a6b6d..5c70bd193 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -23,12 +23,12 @@ class SimulationCase : public ILoggable { * @fn SimulationCase * @brief Constructor */ - SimulationCase(std::string ini_base); + SimulationCase(const std::string initialise_base_file); /** * @fn SimulationCase * @brief Constructor for Monte-Carlo Simulation */ - SimulationCase(std::string ini_base, const MonteCarloSimulationExecutor& monte_carlo_simulator, std::string log_path); + SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path); /** * @fn ~SimulationCase * @brief Destructor @@ -60,10 +60,10 @@ class SimulationCase : public ILoggable { // Getter /** - * @fn GetSimConfig + * @fn GetSimulationConfiguration * @brief Return simulation setting */ - inline SimulationConfig& GetSimConfig() { return sim_config_; } + inline SimulationConfig& GetSimulationConfiguration() { return simulation_configuration_; } /** * @fn GetGlobalEnvironment * @brief Return global environment @@ -71,8 +71,8 @@ class SimulationCase : public ILoggable { inline const GlobalEnvironment& GetGlobalEnvironment() const { return *global_environment_; } protected: - SimulationConfig sim_config_; //!< Simulation setting - GlobalEnvironment* global_environment_; //!< Global Environment + SimulationConfig simulation_configuration_; //!< Simulation setting + GlobalEnvironment* global_environment_; //!< Global Environment }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From df9f46d25ac137fe792919b149dfa54dc1b35dae Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:42:58 +0100 Subject: [PATCH 0927/1086] Fix sample case --- src/simulation/case/sample_case.cpp | 14 +++++++------- src/simulation/case/sample_case.hpp | 4 ++-- .../sample_ground_station.cpp | 2 +- .../sample_ground_station.hpp | 2 +- .../sample_spacecraft/sample_spacecraft.cpp | 2 +- .../sample_spacecraft/sample_spacecraft.hpp | 8 ++++---- 6 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 9a9ca1213..fb95f084a 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -12,20 +12,20 @@ using std::string; SampleCase::SampleCase(string initialise_base_file) : SimulationCase(initialise_base_file) {} -SampleCase::~SampleCase() { delete sample_sat_; } +SampleCase::~SampleCase() { delete sample_spacecraft_; } void SampleCase::Initialize() { // Instantiate the target of the simulation // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini const int spacecraft_id = 0; - sample_sat_ = new SampleSat(&simulation_configuration_, global_environment_, spacecraft_id); + sample_spacecraft_ = new SampleSpacecraft(&simulation_configuration_, global_environment_, spacecraft_id); const int ground_station_id = 0; - sample_gs_ = new SampleGroundStation(&simulation_configuration_, ground_station_id); + sample_ground_station_ = new SampleGroundStation(&simulation_configuration_, ground_station_id); // Register the log output global_environment_->LogSetup(*(simulation_configuration_.main_logger_)); - sample_sat_->LogSetup(*(simulation_configuration_.main_logger_)); - sample_gs_->LogSetup(*(simulation_configuration_.main_logger_)); + sample_spacecraft_->LogSetup(*(simulation_configuration_.main_logger_)); + sample_ground_station_->LogSetup(*(simulation_configuration_.main_logger_)); // Write headers to the log simulation_configuration_.main_logger_->WriteHeaders(); @@ -46,9 +46,9 @@ void SampleCase::Main() { // Global Environment Update global_environment_->Update(); // Spacecraft Update - sample_sat_->Update(&(global_environment_->GetSimulationTime())); + sample_spacecraft_->Update(&(global_environment_->GetSimulationTime())); // Ground Station Update - sample_gs_->Update(global_environment_->GetCelestialInformation().GetEarthRotation(), *sample_sat_); + sample_ground_station_->Update(global_environment_->GetCelestialInformation().GetEarthRotation(), *sample_spacecraft_); // Debug output if (global_environment_->GetSimulationTime().GetState().disp_output) { diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 43142ea25..0e0e7110e 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -52,8 +52,8 @@ class SampleCase : public SimulationCase { virtual std::string GetLogValue() const; private: - SampleSat* sample_sat_; //!< Instance of spacecraft - SampleGroundStation* sample_gs_; //!< Instance of ground station + SampleSpacecraft* sample_spacecraft_; //!< Instance of spacecraft + SampleGroundStation* sample_ground_station_; //!< Instance of ground station }; #endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index 205e30fea..1c7fb0d15 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -21,7 +21,7 @@ void SampleGroundStation::LogSetup(Logger& logger) { components_->CompoLogSetUp(logger); } -void SampleGroundStation::Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft) { +void SampleGroundStation::Update(const CelestialRotation& celestial_rotation, const SampleSpacecraft& spacecraft) { GroundStation::Update(celestial_rotation, spacecraft); components_->GetGsCalculator()->Update(spacecraft, spacecraft.GetInstalledComponents().GetAntenna(), *this, *(components_->GetAntenna())); } diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 1d4a48c85..5f998333a 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -47,7 +47,7 @@ class SampleGroundStation : public GroundStation { * @fn Update * @brief Override function of Update in GroundStation class */ - virtual void Update(const CelestialRotation& celestial_rotation, const SampleSat& spacecraft); + virtual void Update(const CelestialRotation& celestial_rotation, const SampleSpacecraft& spacecraft); private: SampleGsComponents* components_; //!< Ground station related components diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index cd6b7f6b7..973e8ef39 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -10,7 +10,7 @@ #include "sample_components.hpp" -SampleSat::SampleSat(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id) +SampleSpacecraft::SampleSpacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id) : Spacecraft(simulation_configuration, global_environment, spacecraft_id) { sample_components_ = new SampleComponents(dynamics_, structure_, local_environment_, global_environment, simulation_configuration, &clock_generator_, spacecraft_id); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index fa74d57fd..169cd43e9 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -12,16 +12,16 @@ class SampleComponents; /** - * @class SampleSat + * @class SampleSpacecraft * @brief An example of user side spacecraft class */ -class SampleSat : public Spacecraft { +class SampleSpacecraft : public Spacecraft { public: /** - * @fn SampleSat + * @fn SampleSpacecraft * @brief Constructor */ - SampleSat(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id); + SampleSpacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id); /** * @fn GetInstalledComponents From 4f509c268d3efba0bb22c892cc6d6f58c40f9dce Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:44:31 +0100 Subject: [PATCH 0928/1086] Rename Simulationconfig --- src/disturbances/disturbances.cpp | 4 ++-- src/disturbances/disturbances.hpp | 4 ++-- src/dynamics/dynamics.cpp | 4 ++-- src/dynamics/dynamics.hpp | 4 ++-- src/environment/global/global_environment.cpp | 4 ++-- src/environment/global/global_environment.hpp | 4 ++-- src/environment/local/local_environment.cpp | 4 ++-- src/environment/local/local_environment.hpp | 4 ++-- src/simulation/case/simulation_case.hpp | 4 ++-- src/simulation/ground_station/ground_station.cpp | 5 +++-- src/simulation/ground_station/ground_station.hpp | 4 ++-- .../sample_ground_station/sample_ground_station.cpp | 4 ++-- .../sample_ground_station/sample_ground_station.hpp | 4 ++-- .../sample_ground_station_components.cpp | 2 +- .../sample_ground_station_components.hpp | 8 ++++---- .../inter_spacecraft_communication.cpp | 4 +++- .../inter_spacecraft_communication.hpp | 2 +- src/simulation/simulation_configuration.hpp | 8 ++++---- .../sample_spacecraft/sample_components.cpp | 2 +- .../sample_spacecraft/sample_components.hpp | 12 ++++++------ .../sample_spacecraft/sample_spacecraft.cpp | 3 ++- .../sample_spacecraft/sample_spacecraft.hpp | 3 ++- src/simulation/spacecraft/spacecraft.cpp | 9 +++++---- src/simulation/spacecraft/spacecraft.hpp | 11 ++++++----- src/simulation/spacecraft/structure/structure.cpp | 4 ++-- src/simulation/spacecraft/structure/structure.hpp | 4 ++-- 26 files changed, 66 insertions(+), 59 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index 25433880f..b5493d989 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -15,7 +15,7 @@ #include "solar_radiation_pressure_disturbance.hpp" #include "third_body_gravity.hpp" -Disturbances::Disturbances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, +Disturbances::Disturbances(const SimulationConfiguration* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment) { InitializeInstances(simulation_configuration, spacecraft_id, structure, global_environment); InitializeForceAndTorque(); @@ -62,7 +62,7 @@ void Disturbances::LogSetup(Logger& logger) { logger.CopyFileToLogDirectory(initialize_file_name_); } -void Disturbances::InitializeInstances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, +void Disturbances::InitializeInstances(const SimulationConfiguration* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment) { IniAccess ini_access = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); initialize_file_name_ = ini_access.ReadString("SETTING_FILES", "disturbance_file"); diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index e7fb21226..173481ade 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -29,7 +29,7 @@ class Disturbances { * @param [in] structure: Structure information of spacecraft * @param [in] global_environment: Global environment information */ - Disturbances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, + Disturbances(const SimulationConfiguration* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment); /** * @fn ~Disturbances @@ -88,7 +88,7 @@ class Disturbances { * @param [in] structure: Structure information of spacecraft * @param [in] global_environment: Global environment information */ - void InitializeInstances(const SimulationConfig* simulation_configuration, const int spacecraft_id, const Structure* structure, + void InitializeInstances(const SimulationConfiguration* simulation_configuration, const int spacecraft_id, const Structure* structure, const GlobalEnvironment* global_environment); /** * @fn InitializeForceAndTorque diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index 47523050a..a9cf3de49 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -7,7 +7,7 @@ #include "../simulation/multiple_spacecraft/relative_information.hpp" -Dynamics::Dynamics(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, +Dynamics::Dynamics(const SimulationConfiguration* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information) { Initialize(simulation_configuration, simulation_time, local_celestial_information, spacecraft_id, structure, relative_information); @@ -19,7 +19,7 @@ Dynamics::~Dynamics() { delete temperature_; } -void Dynamics::Initialize(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, +void Dynamics::Initialize(const SimulationConfiguration* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information) { structure_ = structure; diff --git a/src/dynamics/dynamics.hpp b/src/dynamics/dynamics.hpp index 3bb221be6..25d17f5bf 100644 --- a/src/dynamics/dynamics.hpp +++ b/src/dynamics/dynamics.hpp @@ -35,7 +35,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] relative_information: Relative information */ - Dynamics(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + Dynamics(const SimulationConfiguration* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information = (RelativeInformation*)nullptr); /** @@ -122,7 +122,7 @@ class Dynamics { * @param [in] structure: Structure of the spacecraft * @param [in] relative_information: Relative information */ - void Initialize(const SimulationConfig* simulation_configuration, const SimulationTime* simulation_time, + void Initialize(const SimulationConfiguration* simulation_configuration, const SimulationTime* simulation_time, const LocalCelestialInformation* local_celestial_information, const int spacecraft_id, Structure* structure, RelativeInformation* relative_information = (RelativeInformation*)nullptr); }; diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index fac66c5a0..0665bca72 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -9,7 +9,7 @@ #include "initialize_gnss_satellites.hpp" #include "library/initialize/initialize_file_access.hpp" -GlobalEnvironment::GlobalEnvironment(SimulationConfig* simulation_configuration) { Initialize(simulation_configuration); } +GlobalEnvironment::GlobalEnvironment(SimulationConfiguration* simulation_configuration) { Initialize(simulation_configuration); } GlobalEnvironment::~GlobalEnvironment() { delete simulation_time_; @@ -18,7 +18,7 @@ GlobalEnvironment::~GlobalEnvironment() { delete gnss_satellites_; } -void GlobalEnvironment::Initialize(SimulationConfig* simulation_configuration) { +void GlobalEnvironment::Initialize(SimulationConfiguration* simulation_configuration) { // Get ini file path IniAccess iniAccess = IniAccess(simulation_configuration->initialize_base_file_name_); std::string simulation_time_ini_path = simulation_configuration->initialize_base_file_name_; diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 1a4170bbd..1076cebc7 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -24,7 +24,7 @@ class GlobalEnvironment { * @brief Constructor * @param [in] simulation_configuration: Simulation configuration */ - GlobalEnvironment(SimulationConfig* simulation_configuration); + GlobalEnvironment(SimulationConfiguration* simulation_configuration); /** * @fn ~GlobalEnvironment * @brief Destructor @@ -36,7 +36,7 @@ class GlobalEnvironment { * @brief Initialize all global environment members * @param [in] simulation_configuration: Simulation configuration */ - void Initialize(SimulationConfig* simulation_configuration); + void Initialize(SimulationConfiguration* simulation_configuration); /** * @fn Update * @brief Update states of all global environment diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 9699bb218..2fb3cac22 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -9,7 +9,7 @@ #include "initialize_local_environment.hpp" #include "library/initialize/initialize_file_access.hpp" -LocalEnvironment::LocalEnvironment(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +LocalEnvironment::LocalEnvironment(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { Initialize(simulation_configuration, global_environment, spacecraft_id); } @@ -21,7 +21,7 @@ LocalEnvironment::~LocalEnvironment() { delete celestial_information_; } -void LocalEnvironment::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +void LocalEnvironment::Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { // Read file name IniAccess iniAccess = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); diff --git a/src/environment/local/local_environment.hpp b/src/environment/local/local_environment.hpp index 6e3afcb23..cb7412a3c 100644 --- a/src/environment/local/local_environment.hpp +++ b/src/environment/local/local_environment.hpp @@ -27,7 +27,7 @@ class LocalEnvironment { * @param [in] global_environment: Global environment * @param [in] spacecraft_id: Satellite ID */ - LocalEnvironment(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + LocalEnvironment(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn ~LocalEnvironment * @brief Destructor @@ -82,7 +82,7 @@ class LocalEnvironment { * @param [in] global_environment: Global environment * @param [in] spacecraft_id: Satellite ID */ - void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + void Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); }; #endif // S2E_ENVIRONMENT_LOCAL_LOCAL_ENVIRONMENT_HPP_ diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 5c70bd193..6a919d463 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -63,7 +63,7 @@ class SimulationCase : public ILoggable { * @fn GetSimulationConfiguration * @brief Return simulation setting */ - inline SimulationConfig& GetSimulationConfiguration() { return simulation_configuration_; } + inline SimulationConfiguration& GetSimulationConfiguration() { return simulation_configuration_; } /** * @fn GetGlobalEnvironment * @brief Return global environment @@ -71,7 +71,7 @@ class SimulationCase : public ILoggable { inline const GlobalEnvironment& GetGlobalEnvironment() const { return *global_environment_; } protected: - SimulationConfig simulation_configuration_; //!< Simulation setting + SimulationConfiguration simulation_configuration_; //!< Simulation setting GlobalEnvironment* global_environment_; //!< Global Environment }; diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 1530b2013..de8b5813b 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -13,7 +13,8 @@ #include #include -GroundStation::GroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id) : ground_station_id_(ground_station_id) { +GroundStation::GroundStation(const SimulationConfiguration* configuration, const unsigned int ground_station_id) + : ground_station_id_(ground_station_id) { Initialize(configuration, ground_station_id_); number_of_spacecraft_ = configuration->number_of_simulated_spacecraft_; for (unsigned int i = 0; i < number_of_spacecraft_; i++) { @@ -23,7 +24,7 @@ GroundStation::GroundStation(const SimulationConfig* configuration, const unsign GroundStation::~GroundStation() {} -void GroundStation::Initialize(const SimulationConfig* configuration, const unsigned int ground_station_id) { +void GroundStation::Initialize(const SimulationConfiguration* configuration, const unsigned int ground_station_id) { std::string gs_ini_path = configuration->ground_station_file_list_[0]; auto conf = IniAccess(gs_ini_path); diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 3c1b06395..9847d0248 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -23,7 +23,7 @@ class GroundStation : public ILoggable { * @fn GroundStation * @brief Constructor */ - GroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id_); + GroundStation(const SimulationConfiguration* configuration, const unsigned int ground_station_id_); /** * @fn ~GroundStation * @brief Destructor @@ -34,7 +34,7 @@ class GroundStation : public ILoggable { * @fn Initialize * @brief Virtual function to initialize the ground station */ - virtual void Initialize(const SimulationConfig* configuration, const unsigned int ground_station_id); + virtual void Initialize(const SimulationConfiguration* configuration, const unsigned int ground_station_id); /** * @fn LogSetup * @brief Virtual function to log output setting for ground station related components diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp index 1c7fb0d15..9671181cd 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp @@ -7,14 +7,14 @@ #include "sample_ground_station_components.hpp" -SampleGroundStation::SampleGroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id) +SampleGroundStation::SampleGroundStation(const SimulationConfiguration* configuration, const unsigned int ground_station_id) : GroundStation(configuration, ground_station_id) { Initialize(configuration); } SampleGroundStation::~SampleGroundStation() { delete components_; } -void SampleGroundStation::Initialize(const SimulationConfig* configuration) { components_ = new SampleGsComponents(configuration); } +void SampleGroundStation::Initialize(const SimulationConfiguration* configuration) { components_ = new SampleGsComponents(configuration); } void SampleGroundStation::LogSetup(Logger& logger) { GroundStation::LogSetup(logger); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 5f998333a..674bdc6ff 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -26,7 +26,7 @@ class SampleGroundStation : public GroundStation { * @fn SampleGroundStation * @brief Constructor */ - SampleGroundStation(const SimulationConfig* configuration, const unsigned int ground_station_id); + SampleGroundStation(const SimulationConfiguration* configuration, const unsigned int ground_station_id); /** * @fn ~SampleGroundStation * @brief Destructor @@ -37,7 +37,7 @@ class SampleGroundStation : public GroundStation { * @fn Initialize * @brief Override function of Initialize in GroundStation class */ - virtual void Initialize(const SimulationConfig* configuration); + virtual void Initialize(const SimulationConfiguration* configuration); /** * @fn LogSetup * @brief Override function of LogSetup in GroundStation class diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp index f9ce949c7..53d5e67f3 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp @@ -6,7 +6,7 @@ #include -SampleGsComponents::SampleGsComponents(const SimulationConfig* configuration) : configuration_(configuration) { +SampleGsComponents::SampleGsComponents(const SimulationConfiguration* configuration) : configuration_(configuration) { IniAccess iniAccess = IniAccess(configuration_->ground_station_file_list_[0]); std::string ant_ini_path = iniAccess.ReadString("COMPONENT_FILES", "ground_station_antenna_file"); diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp index 6cc30d558..1d3549880 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp @@ -19,7 +19,7 @@ class SampleGsComponents { * @fn SampleGsComponents * @brief Constructor */ - SampleGsComponents(const SimulationConfig* configuration); + SampleGsComponents(const SimulationConfiguration* configuration); /** * @fn ~SampleGsComponents * @brief Destructor @@ -44,9 +44,9 @@ class SampleGsComponents { inline GroundStationCalculator* GetGsCalculator() const { return gs_calculator_; } private: - Antenna* antenna_; //!< Antenna on ground station - GroundStationCalculator* gs_calculator_; //!< Ground station calculation algorithm - const SimulationConfig* configuration_; //!< Simulation setting + Antenna* antenna_; //!< Antenna on ground station + GroundStationCalculator* gs_calculator_; //!< Ground station calculation algorithm + const SimulationConfiguration* configuration_; //!< Simulation setting }; #endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp index 300e8b4d5..6e4678aee 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.cpp @@ -7,6 +7,8 @@ #include -InterSpacecraftCommunication::InterSpacecraftCommunication(const SimulationConfig* simulation_configuration) { UNUSED(simulation_configuration); } +InterSpacecraftCommunication::InterSpacecraftCommunication(const SimulationConfiguration* simulation_configuration) { + UNUSED(simulation_configuration); +} InterSpacecraftCommunication::~InterSpacecraftCommunication() {} diff --git a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp index 44ba54869..11b32008e 100644 --- a/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp +++ b/src/simulation/multiple_spacecraft/inter_spacecraft_communication.hpp @@ -18,7 +18,7 @@ class InterSpacecraftCommunication { * @fn InterSpacecraftCommunication * @brief Constructor */ - InterSpacecraftCommunication(const SimulationConfig* simulation_configuration); + InterSpacecraftCommunication(const SimulationConfiguration* simulation_configuration); /** * @fn ~InterSpacecraftCommunication * @brief Destructor diff --git a/src/simulation/simulation_configuration.hpp b/src/simulation/simulation_configuration.hpp index 65cbe2ae3..25bde1245 100644 --- a/src/simulation/simulation_configuration.hpp +++ b/src/simulation/simulation_configuration.hpp @@ -12,10 +12,10 @@ #include "../library/logger/logger.hpp" /** - * @struct SimulationConfig + * @struct SimulationConfiguration * @brief Simulation setting information */ -struct SimulationConfig { +struct SimulationConfiguration { std::string initialize_base_file_name_; //!< Base file name for initialization Logger* main_logger_; //!< Main logger @@ -29,10 +29,10 @@ struct SimulationConfig { std::string gnss_file_; //!< File name for GNSS initialization /** - * @fn ~SimulationConfig + * @fn ~SimulationConfiguration * @brief Destructor */ - ~SimulationConfig() { delete main_logger_; } + ~SimulationConfiguration() { delete main_logger_; } }; #endif // S2E_SIMULATION_SIMULATION_CONFIGURATION_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 7e295f256..4bce66337 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -10,7 +10,7 @@ #include "sample_port_configuration.hpp" SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, - const GlobalEnvironment* global_environment, const SimulationConfig* configuration, + const GlobalEnvironment* global_environment, const SimulationConfiguration* configuration, ClockGenerator* clock_generator, const unsigned int spacecraft_id) : configuration_(configuration), dynamics_(dynamics), diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp index d8a29ea3c..1b8a5f383 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp @@ -54,7 +54,7 @@ class SampleComponents : public InstalledComponents { * @brief Constructor */ SampleComponents(const Dynamics* dynamics, Structure* structure, const LocalEnvironment* local_environment, - const GlobalEnvironment* global_environment, const SimulationConfig* configuration, ClockGenerator* clock_generator, + const GlobalEnvironment* global_environment, const SimulationConfiguration* configuration, ClockGenerator* clock_generator, const unsigned int spacecraft_id); /** * @fn ~SampleComponents @@ -112,11 +112,11 @@ class SampleComponents : public InstalledComponents { */ // States - const SimulationConfig* configuration_; //!< Simulation settings - const Dynamics* dynamics_; //!< Dynamics information of the spacecraft - Structure* structure_; //!< Structure information of the spacecraft - const LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft - const GlobalEnvironment* global_environment_; //!< Global environment information + const SimulationConfiguration* configuration_; //!< Simulation settings + const Dynamics* dynamics_; //!< Dynamics information of the spacecraft + Structure* structure_; //!< Structure information of the spacecraft + const LocalEnvironment* local_environment_; //!< Local environment information around the spacecraft + const GlobalEnvironment* global_environment_; //!< Global environment information }; #endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp index 973e8ef39..c162ffab8 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp @@ -10,7 +10,8 @@ #include "sample_components.hpp" -SampleSpacecraft::SampleSpacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id) +SampleSpacecraft::SampleSpacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, + const unsigned int spacecraft_id) : Spacecraft(simulation_configuration, global_environment, spacecraft_id) { sample_components_ = new SampleComponents(dynamics_, structure_, local_environment_, global_environment, simulation_configuration, &clock_generator_, spacecraft_id); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp index 169cd43e9..a3d21e020 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp @@ -21,7 +21,8 @@ class SampleSpacecraft : public Spacecraft { * @fn SampleSpacecraft * @brief Constructor */ - SampleSpacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const unsigned int spacecraft_id); + SampleSpacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, + const unsigned int spacecraft_id); /** * @fn GetInstalledComponents diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index c3d25b6bd..dce592086 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -8,12 +8,12 @@ #include #include -Spacecraft::Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) +Spacecraft::Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) : spacecraft_id_(spacecraft_id) { Initialize(simulation_configuration, global_environment, spacecraft_id); } -Spacecraft::Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +Spacecraft::Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id) : spacecraft_id_(spacecraft_id) { Initialize(simulation_configuration, global_environment, relative_information, spacecraft_id); @@ -30,7 +30,8 @@ Spacecraft::~Spacecraft() { delete components_; } -void Spacecraft::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) { +void Spacecraft::Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, + const int spacecraft_id) { clock_generator_.ClearTimerCount(); structure_ = new Structure(simulation_configuration, spacecraft_id); local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); @@ -43,7 +44,7 @@ void Spacecraft::Initialize(const SimulationConfig* simulation_configuration, co relative_information_ = nullptr; } -void Spacecraft::Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, +void Spacecraft::Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id) { clock_generator_.ClearTimerCount(); structure_ = new Structure(simulation_configuration, spacecraft_id); diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 2f1abdd20..5baf27f33 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -25,13 +25,13 @@ class Spacecraft { * @fn Spacecraft * @brief Constructor for single satellite simulation */ - Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); /** * @fn Spacecraft * @brief Constructor for multiple satellite simulation */ - Spacecraft(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, - const int spacecraft_id); + Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, + RelativeInformation* relative_information, const int spacecraft_id); /** * @fn ~Spacecraft @@ -48,12 +48,13 @@ class Spacecraft { * @fn Initialize * @brief Initialize function for single spacecraft simulation */ - virtual void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); + virtual void Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, + const int spacecraft_id); /** * @fn Initialize * @brief Initialize function for multiple spacecraft simulation */ - virtual void Initialize(const SimulationConfig* simulation_configuration, const GlobalEnvironment* global_environment, + virtual void Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, RelativeInformation* relative_information, const int spacecraft_id); /** diff --git a/src/simulation/spacecraft/structure/structure.cpp b/src/simulation/spacecraft/structure/structure.cpp index 92e8bc0ba..b16de8b09 100644 --- a/src/simulation/spacecraft/structure/structure.cpp +++ b/src/simulation/spacecraft/structure/structure.cpp @@ -8,7 +8,7 @@ #include #include -Structure::Structure(const SimulationConfig* simulation_configuration, const int spacecraft_id) { +Structure::Structure(const SimulationConfiguration* simulation_configuration, const int spacecraft_id) { Initialize(simulation_configuration, spacecraft_id); } @@ -17,7 +17,7 @@ Structure::~Structure() { delete residual_magnetic_moment_; } -void Structure::Initialize(const SimulationConfig* simulation_configuration, const int spacecraft_id) { +void Structure::Initialize(const SimulationConfiguration* simulation_configuration, const int spacecraft_id) { // Read file name IniAccess conf = IniAccess(simulation_configuration->spacecraft_file_list_[spacecraft_id]); std::string ini_fname = conf.ReadString("SETTING_FILES", "structure_file"); diff --git a/src/simulation/spacecraft/structure/structure.hpp b/src/simulation/spacecraft/structure/structure.hpp index be2bfdb20..acc0b5d36 100644 --- a/src/simulation/spacecraft/structure/structure.hpp +++ b/src/simulation/spacecraft/structure/structure.hpp @@ -23,7 +23,7 @@ class Structure { * @fn Structure * @brief Constructor */ - Structure(const SimulationConfig* simulation_configuration, const int spacecraft_id); + Structure(const SimulationConfiguration* simulation_configuration, const int spacecraft_id); /** * @fn ~Structure * @brief Destructor @@ -33,7 +33,7 @@ class Structure { * @fn Initialize * @brief Initialize function */ - void Initialize(const SimulationConfig* simulation_configuration, const int spacecraft_id); + void Initialize(const SimulationConfiguration* simulation_configuration, const int spacecraft_id); // Getter /** From 5f96d0bab7cfa7fe589acf1bc998c89dc163bf4a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:45:12 +0100 Subject: [PATCH 0929/1086] Fix main --- src/s2e.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/s2e.cpp b/src/s2e.cpp index 0511763a9..c3eca722d 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -68,9 +68,9 @@ int main(int argc, char *argv[]) std::cout << "\tIni file: "; print_path(ini_file); - auto simcase = SampleCase(ini_file); - simcase.Initialize(); - simcase.Main(); + auto simulation_case = SampleCase(ini_file); + simulation_case.Initialize(); + simulation_case.Main(); end = system_clock::now(); double time = static_cast(duration_cast(end - start).count() / 1000000.0); From 7c91fb397e828eb4fffee6ebd68b9f5c539070c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 16:52:45 +0100 Subject: [PATCH 0930/1086] Fix format --- src/simulation/case/simulation_case.cpp | 28 ++++++++++++------------- src/simulation/case/simulation_case.hpp | 2 +- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 2de83349b..0f87e82ba 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -10,24 +10,24 @@ #include SimulationCase::SimulationCase(const std::string initialise_base_file) { - IniAccess simbase_ini = IniAccess(initialise_base_file); + IniAccess simulation_base_ini = IniAccess(initialise_base_file); const char* section = "SIMULATION_SETTINGS"; simulation_configuration_.initialize_base_file_name_ = initialise_base_file; simulation_configuration_.main_logger_ = InitLog(simulation_configuration_.initialize_base_file_name_); - simulation_configuration_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - simulation_configuration_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + simulation_configuration_.number_of_simulated_spacecraft_ = simulation_base_ini.ReadInt(section, "number_of_simulated_spacecraft"); + simulation_configuration_.spacecraft_file_list_ = simulation_base_ini.ReadStrVector(section, "spacecraft_file"); - simulation_configuration_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); - simulation_configuration_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + simulation_configuration_.number_of_simulated_ground_station_ = simulation_base_ini.ReadInt(section, "number_of_simulated_ground_station"); + simulation_configuration_.ground_station_file_list_ = simulation_base_ini.ReadStrVector(section, "ground_station_file"); - simulation_configuration_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); - simulation_configuration_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); + simulation_configuration_.inter_sc_communication_file_ = simulation_base_ini.ReadString(section, "inter_sat_comm_file"); + simulation_configuration_.gnss_file_ = simulation_base_ini.ReadString(section, "gnss_file"); global_environment_ = new GlobalEnvironment(&simulation_configuration_); } SimulationCase::SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { - IniAccess simbase_ini = IniAccess(initialise_base_file); + IniAccess simulation_base_ini = IniAccess(initialise_base_file); const char* section = "SIMULATION_SETTINGS"; simulation_configuration_.initialize_base_file_name_ = initialise_base_file; // Log for Monte Carlo Simulation @@ -35,14 +35,14 @@ SimulationCase::SimulationCase(const std::string initialise_base_file, const Mon // ToDo: Consider that `enable_inilog = false` is fine or not? simulation_configuration_.main_logger_ = new Logger(log_file_name, log_path, initialise_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); - simulation_configuration_.number_of_simulated_spacecraft_ = simbase_ini.ReadInt(section, "number_of_simulated_spacecraft"); - simulation_configuration_.spacecraft_file_list_ = simbase_ini.ReadStrVector(section, "spacecraft_file"); + simulation_configuration_.number_of_simulated_spacecraft_ = simulation_base_ini.ReadInt(section, "number_of_simulated_spacecraft"); + simulation_configuration_.spacecraft_file_list_ = simulation_base_ini.ReadStrVector(section, "spacecraft_file"); - simulation_configuration_.number_of_simulated_ground_station_ = simbase_ini.ReadInt(section, "number_of_simulated_ground_station"); - simulation_configuration_.ground_station_file_list_ = simbase_ini.ReadStrVector(section, "ground_station_file"); + simulation_configuration_.number_of_simulated_ground_station_ = simulation_base_ini.ReadInt(section, "number_of_simulated_ground_station"); + simulation_configuration_.ground_station_file_list_ = simulation_base_ini.ReadStrVector(section, "ground_station_file"); - simulation_configuration_.inter_sc_communication_file_ = simbase_ini.ReadString(section, "inter_sat_comm_file"); - simulation_configuration_.gnss_file_ = simbase_ini.ReadString(section, "gnss_file"); + simulation_configuration_.inter_sc_communication_file_ = simulation_base_ini.ReadString(section, "inter_sat_comm_file"); + simulation_configuration_.gnss_file_ = simulation_base_ini.ReadString(section, "gnss_file"); // Global Environment global_environment_ = new GlobalEnvironment(&simulation_configuration_); } diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 6a919d463..fe2f468d1 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -72,7 +72,7 @@ class SimulationCase : public ILoggable { protected: SimulationConfiguration simulation_configuration_; //!< Simulation setting - GlobalEnvironment* global_environment_; //!< Global Environment + GlobalEnvironment* global_environment_; //!< Global Environment }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From fa0903fbe3c1af810f310670a6705f8434d2a064 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 20:44:38 +0100 Subject: [PATCH 0931/1086] Fix gnss satellite id --- src/environment/global/gnss_satellites.cpp | 398 +++++++++++---------- src/environment/global/gnss_satellites.hpp | 68 ++-- 2 files changed, 236 insertions(+), 230 deletions(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 8037371f0..9397840f3 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -219,9 +219,9 @@ string GnssSat_coordinate::GetIDFromIndex(int index) const { int GnssSat_coordinate::GetNumOfSatellites() const { return all_sat_num_; } -bool GnssSat_coordinate::GetWhetherValid(int spacecraft_id) const { - if (spacecraft_id >= all_sat_num_) return false; - return validate_.at(spacecraft_id); +bool GnssSat_coordinate::GetWhetherValid(int gnss_satellite_id) const { + if (gnss_satellite_id >= all_sat_num_) return false; + return validate_.at(gnss_satellite_id); } pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, UR_KINDS ur_flag) { @@ -313,7 +313,7 @@ pair GnssSat_position::Init(vector>& file, int in iss >> tmp; s.push_back(tmp); } - int spacecraft_id = GetIndexFromID(s.front()); + int gnss_satellite_id = GetIndexFromID(s.front()); bool available_flag = true; libra::Vector<3> ecef_position_m(0.0); @@ -340,14 +340,14 @@ pair GnssSat_position::Init(vector>& file, int in eci_position(1) = sin_ * x + cos_ * y; eci_position(2) = z; - if (!unixtime_vector_.at(spacecraft_id).empty() && std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1.0) { - unixtime_vector_.at(spacecraft_id).back() = unix_time; - gnss_sat_table_ecef_.at(spacecraft_id).back() = ecef_position_m; - gnss_sat_table_eci_.at(spacecraft_id).back() = eci_position; + if (!unixtime_vector_.at(gnss_satellite_id).empty() && std::abs(unix_time - unixtime_vector_.at(gnss_satellite_id).back()) < 1.0) { + unixtime_vector_.at(gnss_satellite_id).back() = unix_time; + gnss_sat_table_ecef_.at(gnss_satellite_id).back() = ecef_position_m; + gnss_sat_table_eci_.at(gnss_satellite_id).back() = eci_position; } else { - unixtime_vector_.at(spacecraft_id).emplace_back(unix_time); - gnss_sat_table_ecef_.at(spacecraft_id).emplace_back(ecef_position_m); - gnss_sat_table_eci_.at(spacecraft_id).emplace_back(eci_position); + unixtime_vector_.at(gnss_satellite_id).emplace_back(unix_time); + gnss_sat_table_ecef_.at(gnss_satellite_id).emplace_back(ecef_position_m); + gnss_sat_table_eci_.at(gnss_satellite_id).emplace_back(eci_position); } } } @@ -369,137 +369,140 @@ void GnssSat_position::SetUp(const double start_unix_time, const double step_sec ecef_.resize(all_sat_num_); eci_.resize(all_sat_num_); - for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { - if (unixtime_vector_.at(spacecraft_id).empty()) { - validate_.at(spacecraft_id) = false; + for (int gnss_satellite_id = 0; gnss_satellite_id < all_sat_num_; ++gnss_satellite_id) { + if (unixtime_vector_.at(gnss_satellite_id).empty()) { + validate_.at(gnss_satellite_id) = false; continue; } - int index = lower_bound(unixtime_vector_.at(spacecraft_id).begin(), unixtime_vector_.at(spacecraft_id).end(), start_unix_time) - - unixtime_vector_.at(spacecraft_id).begin(); - if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { - nearest_index_.at(spacecraft_id) = index; - validate_.at(spacecraft_id) = false; + int index = lower_bound(unixtime_vector_.at(gnss_satellite_id).begin(), unixtime_vector_.at(gnss_satellite_id).end(), start_unix_time) - + unixtime_vector_.at(gnss_satellite_id).begin(); + if (index == (int)unixtime_vector_.at(gnss_satellite_id).size()) { + nearest_index_.at(gnss_satellite_id) = index; + validate_.at(gnss_satellite_id) = false; continue; } - double nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); + double nearest_unixtime = unixtime_vector_.at(gnss_satellite_id).at(index); if (interpolation_number_ % 2 && index != 0) { - double pre_time = unixtime_vector_.at(spacecraft_id).at(index - 1); + double pre_time = unixtime_vector_.at(gnss_satellite_id).at(index - 1); if (std::abs(start_unix_time - pre_time) < std::abs(start_unix_time - nearest_unixtime)) --index; } - nearest_index_.at(spacecraft_id) = index; - nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); + nearest_index_.at(gnss_satellite_id) = index; + nearest_unixtime = unixtime_vector_.at(gnss_satellite_id).at(index); if (std::abs(start_unix_time - nearest_unixtime) > time_interval_) { - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(gnss_satellite_id).size()) continue; - time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); - ecef_.at(spacecraft_id).push_back(gnss_sat_table_ecef_.at(spacecraft_id).at(now_index)); - eci_.at(spacecraft_id).push_back(gnss_sat_table_eci_.at(spacecraft_id).at(now_index)); + time_period_.at(gnss_satellite_id).push_back(unixtime_vector_.at(gnss_satellite_id).at(now_index)); + ecef_.at(gnss_satellite_id).push_back(gnss_sat_table_ecef_.at(gnss_satellite_id).at(now_index)); + eci_.at(gnss_satellite_id).push_back(gnss_sat_table_eci_.at(gnss_satellite_id).at(now_index)); } - if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { - validate_.at(spacecraft_id) = false; + if ((int)time_period_.at(gnss_satellite_id).size() != interpolation_number_) { + validate_.at(gnss_satellite_id) = false; continue; } - double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); + double time_period_length = time_period_.at(gnss_satellite_id).back() - time_period_.at(gnss_satellite_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1 + 3) + 1e-4) { // allow for 3 missing - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } else { - validate_.at(spacecraft_id) = true; + validate_.at(gnss_satellite_id) = true; } if (std::abs(start_unix_time - nearest_unixtime) < 1e-4) { // for the numerical error, plus 1e-4 - gnss_sat_ecef_.at(spacecraft_id) = gnss_sat_table_ecef_.at(spacecraft_id).at(index); - gnss_sat_eci_.at(spacecraft_id) = gnss_sat_table_eci_.at(spacecraft_id).at(index); + gnss_sat_ecef_.at(gnss_satellite_id) = gnss_sat_table_ecef_.at(gnss_satellite_id).at(index); + gnss_sat_eci_.at(gnss_satellite_id) = gnss_sat_table_eci_.at(gnss_satellite_id).at(index); } else { - gnss_sat_ecef_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), ecef_.at(spacecraft_id), start_unix_time); - gnss_sat_eci_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), eci_.at(spacecraft_id), start_unix_time); + gnss_sat_ecef_.at(gnss_satellite_id) = + TrigonometricInterpolation(time_period_.at(gnss_satellite_id), ecef_.at(gnss_satellite_id), start_unix_time); + gnss_sat_eci_.at(gnss_satellite_id) = + TrigonometricInterpolation(time_period_.at(gnss_satellite_id), eci_.at(gnss_satellite_id), start_unix_time); } } } void GnssSat_position::Update(const double now_unix_time) { - for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { - if (unixtime_vector_.at(spacecraft_id).empty()) { - validate_.at(spacecraft_id) = false; + for (int gnss_satellite_id = 0; gnss_satellite_id < all_sat_num_; ++gnss_satellite_id) { + if (unixtime_vector_.at(gnss_satellite_id).empty()) { + validate_.at(gnss_satellite_id) = false; continue; } - int index = nearest_index_.at(spacecraft_id); - if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { - validate_.at(spacecraft_id) = false; + int index = nearest_index_.at(gnss_satellite_id); + if (index == (int)unixtime_vector_.at(gnss_satellite_id).size()) { + validate_.at(gnss_satellite_id) = false; continue; } - if (index + 1 < (int)unixtime_vector_.at(spacecraft_id).size()) { - double pre_unix = unixtime_vector_.at(spacecraft_id).at(index); - double post_unix = unixtime_vector_.at(spacecraft_id).at(index + 1); + if (index + 1 < (int)unixtime_vector_.at(gnss_satellite_id).size()) { + double pre_unix = unixtime_vector_.at(gnss_satellite_id).at(index); + double post_unix = unixtime_vector_.at(gnss_satellite_id).at(index + 1); if (std::abs(now_unix_time - post_unix) < std::abs(now_unix_time - pre_unix)) { ++index; - nearest_index_.at(spacecraft_id) = index; + nearest_index_.at(gnss_satellite_id) = index; - time_period_.at(spacecraft_id).clear(); - ecef_.at(spacecraft_id).clear(); - eci_.at(spacecraft_id).clear(); + time_period_.at(gnss_satellite_id).clear(); + ecef_.at(gnss_satellite_id).clear(); + eci_.at(gnss_satellite_id).clear(); // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(gnss_satellite_id).size()) continue; - time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); - ecef_.at(spacecraft_id).push_back(gnss_sat_table_ecef_.at(spacecraft_id).at(now_index)); - eci_.at(spacecraft_id).push_back(gnss_sat_table_eci_.at(spacecraft_id).at(now_index)); + time_period_.at(gnss_satellite_id).push_back(unixtime_vector_.at(gnss_satellite_id).at(now_index)); + ecef_.at(gnss_satellite_id).push_back(gnss_sat_table_ecef_.at(gnss_satellite_id).at(now_index)); + eci_.at(gnss_satellite_id).push_back(gnss_sat_table_eci_.at(gnss_satellite_id).at(now_index)); } } } - double nearest_unix_time = unixtime_vector_.at(spacecraft_id).at(index); + double nearest_unix_time = unixtime_vector_.at(gnss_satellite_id).at(index); if (std::abs(now_unix_time - nearest_unix_time) > time_interval_) { - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } - if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { - validate_.at(spacecraft_id) = false; + if ((int)time_period_.at(gnss_satellite_id).size() != interpolation_number_) { + validate_.at(gnss_satellite_id) = false; continue; } - double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); + double time_period_length = time_period_.at(gnss_satellite_id).back() - time_period_.at(gnss_satellite_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1 + 3) + 1e-4) { // allow for 3 missing - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } else { - validate_.at(spacecraft_id) = true; + validate_.at(gnss_satellite_id) = true; } if (std::abs(now_unix_time - nearest_unix_time) < 1e-4) { // for the numerical error, plus 1e-4 - gnss_sat_ecef_.at(spacecraft_id) = gnss_sat_table_ecef_.at(spacecraft_id).at(index); - gnss_sat_eci_.at(spacecraft_id) = gnss_sat_table_eci_.at(spacecraft_id).at(index); + gnss_sat_ecef_.at(gnss_satellite_id) = gnss_sat_table_ecef_.at(gnss_satellite_id).at(index); + gnss_sat_eci_.at(gnss_satellite_id) = gnss_sat_table_eci_.at(gnss_satellite_id).at(index); } else { - gnss_sat_ecef_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), ecef_.at(spacecraft_id), now_unix_time); - gnss_sat_eci_.at(spacecraft_id) = TrigonometricInterpolation(time_period_.at(spacecraft_id), eci_.at(spacecraft_id), now_unix_time); + gnss_sat_ecef_.at(gnss_satellite_id) = + TrigonometricInterpolation(time_period_.at(gnss_satellite_id), ecef_.at(gnss_satellite_id), now_unix_time); + gnss_sat_eci_.at(gnss_satellite_id) = TrigonometricInterpolation(time_period_.at(gnss_satellite_id), eci_.at(gnss_satellite_id), now_unix_time); } } } -libra::Vector<3> GnssSat_position::GetSatEcef(int spacecraft_id) const { - if (spacecraft_id >= all_sat_num_) return libra::Vector<3>(0.0); - return gnss_sat_ecef_.at(spacecraft_id); +libra::Vector<3> GnssSat_position::GetSatEcef(int gnss_satellite_id) const { + if (gnss_satellite_id >= all_sat_num_) return libra::Vector<3>(0.0); + return gnss_sat_ecef_.at(gnss_satellite_id); } -libra::Vector<3> GnssSat_position::GetSatEci(int spacecraft_id) const { - if (spacecraft_id >= all_sat_num_) return libra::Vector<3>(0.0); - return gnss_sat_eci_.at(spacecraft_id); +libra::Vector<3> GnssSat_position::GetSatEci(int gnss_satellite_id) const { + if (gnss_satellite_id >= all_sat_num_) return libra::Vector<3>(0.0); + return gnss_sat_eci_.at(gnss_satellite_id); } void GnssSat_clock::Init(vector>& file, string file_extension, int interpolation_number, UR_KINDS ur_flag, @@ -573,19 +576,19 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in iss >> tmp; s.push_back(tmp); } - int spacecraft_id = GetIndexFromID(s.front()); + int gnss_satellite_id = GetIndexFromID(s.front()); double clock = stod(s.at(4)); if (std::abs(clock - nan99) < 1.0) continue; // in the file, clock bias is expressed in [micro second], so by multiplying by the speed_of_light & 1e-6, they are converted to [m] clock *= (environment::speed_of_light_m_s * 1e-6); - if (!unixtime_vector_.at(spacecraft_id).empty() && std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1.0) { - unixtime_vector_.at(spacecraft_id).back() = unix_time; - gnss_sat_clock_table_.at(spacecraft_id).back() = clock; + if (!unixtime_vector_.at(gnss_satellite_id).empty() && std::abs(unix_time - unixtime_vector_.at(gnss_satellite_id).back()) < 1.0) { + unixtime_vector_.at(gnss_satellite_id).back() = unix_time; + gnss_sat_clock_table_.at(gnss_satellite_id).back() = clock; } else { - unixtime_vector_.at(spacecraft_id).push_back(unix_time); - gnss_sat_clock_table_.at(spacecraft_id).emplace_back(clock); + unixtime_vector_.at(gnss_satellite_id).push_back(unix_time); + gnss_sat_clock_table_.at(gnss_satellite_id).emplace_back(clock); } } } @@ -633,19 +636,19 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in std::free(time_tm); - int spacecraft_id = GetIndexFromID(s.at(1)); + int gnss_satellite_id = GetIndexFromID(s.at(1)); double clock_bias = stod(s.at(9)) * environment::speed_of_light_m_s; // [s] -> [m] if (start_unix_time - unix_time > 1e-4) continue; // for the numerical error if (end_unix_time - unix_time < 1e-4) break; - if (!unixtime_vector_.at(spacecraft_id).empty() && - std::abs(unix_time - unixtime_vector_.at(spacecraft_id).back()) < 1e-4) { // for the numerical error - unixtime_vector_.at(spacecraft_id).back() = unix_time; - gnss_sat_clock_table_.at(spacecraft_id).back() = clock_bias; + if (!unixtime_vector_.at(gnss_satellite_id).empty() && + std::abs(unix_time - unixtime_vector_.at(gnss_satellite_id).back()) < 1e-4) { // for the numerical error + unixtime_vector_.at(gnss_satellite_id).back() = unix_time; + gnss_sat_clock_table_.at(gnss_satellite_id).back() = clock_bias; } else { - if (!unixtime_vector_.at(spacecraft_id).empty()) - time_interval_ = min(time_interval_, unix_time - unixtime_vector_.at(spacecraft_id).back()); - unixtime_vector_.at(spacecraft_id).emplace_back(unix_time); - gnss_sat_clock_table_.at(spacecraft_id).emplace_back(clock_bias); + if (!unixtime_vector_.at(gnss_satellite_id).empty()) + time_interval_ = min(time_interval_, unix_time - unixtime_vector_.at(gnss_satellite_id).back()); + unixtime_vector_.at(gnss_satellite_id).emplace_back(unix_time); + gnss_sat_clock_table_.at(gnss_satellite_id).emplace_back(clock_bias); } } } @@ -663,126 +666,128 @@ void GnssSat_clock::SetUp(const double start_unix_time, const double step_sec) { clock_bias_.resize(all_sat_num_); - for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { - if (unixtime_vector_.at(spacecraft_id).empty()) { - validate_.at(spacecraft_id) = false; + for (int gnss_satellite_id = 0; gnss_satellite_id < all_sat_num_; ++gnss_satellite_id) { + if (unixtime_vector_.at(gnss_satellite_id).empty()) { + validate_.at(gnss_satellite_id) = false; continue; } - int index = lower_bound(unixtime_vector_.at(spacecraft_id).begin(), unixtime_vector_.at(spacecraft_id).end(), start_unix_time) - - unixtime_vector_.at(spacecraft_id).begin(); - if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { - validate_.at(spacecraft_id) = false; - nearest_index_.at(spacecraft_id) = index; + int index = lower_bound(unixtime_vector_.at(gnss_satellite_id).begin(), unixtime_vector_.at(gnss_satellite_id).end(), start_unix_time) - + unixtime_vector_.at(gnss_satellite_id).begin(); + if (index == (int)unixtime_vector_.at(gnss_satellite_id).size()) { + validate_.at(gnss_satellite_id) = false; + nearest_index_.at(gnss_satellite_id) = index; continue; } - double nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); + double nearest_unixtime = unixtime_vector_.at(gnss_satellite_id).at(index); if (interpolation_number_ % 2 && index != 0) { - double pre_time = unixtime_vector_.at(spacecraft_id).at(index - 1); + double pre_time = unixtime_vector_.at(gnss_satellite_id).at(index - 1); if (std::abs(start_unix_time - pre_time) < std::abs(start_unix_time - nearest_unixtime)) --index; } - nearest_index_.at(spacecraft_id) = index; - nearest_unixtime = unixtime_vector_.at(spacecraft_id).at(index); + nearest_index_.at(gnss_satellite_id) = index; + nearest_unixtime = unixtime_vector_.at(gnss_satellite_id).at(index); if (std::abs(start_unix_time - nearest_unixtime) > time_interval_) { - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(gnss_satellite_id).size()) continue; - time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); - clock_bias_.at(spacecraft_id).push_back(gnss_sat_clock_table_.at(spacecraft_id).at(now_index)); + time_period_.at(gnss_satellite_id).push_back(unixtime_vector_.at(gnss_satellite_id).at(now_index)); + clock_bias_.at(gnss_satellite_id).push_back(gnss_sat_clock_table_.at(gnss_satellite_id).at(now_index)); } - if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { - validate_.at(spacecraft_id) = false; + if ((int)time_period_.at(gnss_satellite_id).size() != interpolation_number_) { + validate_.at(gnss_satellite_id) = false; continue; } - double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); + double time_period_length = time_period_.at(gnss_satellite_id).back() - time_period_.at(gnss_satellite_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1) + 1e-4) { // more strict for clock_bias - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } else { - validate_.at(spacecraft_id) = true; + validate_.at(gnss_satellite_id) = true; } if (std::abs(start_unix_time - nearest_unixtime) < 1e-4) { // for the numerical error - gnss_sat_clock_.at(spacecraft_id) = gnss_sat_clock_table_.at(spacecraft_id).at(index); + gnss_sat_clock_.at(gnss_satellite_id) = gnss_sat_clock_table_.at(gnss_satellite_id).at(index); } else { - gnss_sat_clock_.at(spacecraft_id) = LagrangeInterpolation(time_period_.at(spacecraft_id), clock_bias_.at(spacecraft_id), start_unix_time); + gnss_sat_clock_.at(gnss_satellite_id) = + LagrangeInterpolation(time_period_.at(gnss_satellite_id), clock_bias_.at(gnss_satellite_id), start_unix_time); } } } void GnssSat_clock::Update(const double now_unix_time) { - for (int spacecraft_id = 0; spacecraft_id < all_sat_num_; ++spacecraft_id) { - if (unixtime_vector_.at(spacecraft_id).empty()) { - validate_.at(spacecraft_id) = false; + for (int gnss_satellite_id = 0; gnss_satellite_id < all_sat_num_; ++gnss_satellite_id) { + if (unixtime_vector_.at(gnss_satellite_id).empty()) { + validate_.at(gnss_satellite_id) = false; continue; } - int index = nearest_index_.at(spacecraft_id); - if (index == (int)unixtime_vector_.at(spacecraft_id).size()) { - validate_.at(spacecraft_id) = false; + int index = nearest_index_.at(gnss_satellite_id); + if (index == (int)unixtime_vector_.at(gnss_satellite_id).size()) { + validate_.at(gnss_satellite_id) = false; continue; } - if (index + 1 < (int)unixtime_vector_.at(spacecraft_id).size()) { - double pre_unix = unixtime_vector_.at(spacecraft_id).at(index); - double post_unix = unixtime_vector_.at(spacecraft_id).at(index + 1); + if (index + 1 < (int)unixtime_vector_.at(gnss_satellite_id).size()) { + double pre_unix = unixtime_vector_.at(gnss_satellite_id).at(index); + double post_unix = unixtime_vector_.at(gnss_satellite_id).at(index + 1); if (std::abs(now_unix_time - post_unix) < std::abs(now_unix_time - pre_unix)) { ++index; - nearest_index_.at(spacecraft_id) = index; + nearest_index_.at(gnss_satellite_id) = index; - time_period_.at(spacecraft_id).clear(); - clock_bias_.at(spacecraft_id).clear(); + time_period_.at(gnss_satellite_id).clear(); + clock_bias_.at(gnss_satellite_id).clear(); // for both even and odd: 2n+1 -> [-n, n] 2n -> [-n, n) for (int j = -interpolation_number_ / 2; j < (interpolation_number_ + 1) / 2; ++j) { int now_index = index + j; - if (now_index < 0 || now_index >= (int)unixtime_vector_.at(spacecraft_id).size()) continue; + if (now_index < 0 || now_index >= (int)unixtime_vector_.at(gnss_satellite_id).size()) continue; - time_period_.at(spacecraft_id).push_back(unixtime_vector_.at(spacecraft_id).at(now_index)); - clock_bias_.at(spacecraft_id).push_back(gnss_sat_clock_table_.at(spacecraft_id).at(now_index)); + time_period_.at(gnss_satellite_id).push_back(unixtime_vector_.at(gnss_satellite_id).at(now_index)); + clock_bias_.at(gnss_satellite_id).push_back(gnss_sat_clock_table_.at(gnss_satellite_id).at(now_index)); } } } - if ((int)time_period_.at(spacecraft_id).size() != interpolation_number_) { - validate_.at(spacecraft_id) = false; + if ((int)time_period_.at(gnss_satellite_id).size() != interpolation_number_) { + validate_.at(gnss_satellite_id) = false; continue; } - double nearest_unix_time = unixtime_vector_.at(spacecraft_id).at(index); + double nearest_unix_time = unixtime_vector_.at(gnss_satellite_id).at(index); if (std::abs(now_unix_time - nearest_unix_time) > time_interval_) { - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } // in clock_bias, more strict. - double time_period_length = time_period_.at(spacecraft_id).back() - time_period_.at(spacecraft_id).front(); + double time_period_length = time_period_.at(gnss_satellite_id).back() - time_period_.at(gnss_satellite_id).front(); if (time_period_length > time_interval_ * (interpolation_number_ - 1) + 1e-4) { // more strict for clock_bias - validate_.at(spacecraft_id) = false; + validate_.at(gnss_satellite_id) = false; continue; } else { - validate_.at(spacecraft_id) = true; + validate_.at(gnss_satellite_id) = true; } if (std::abs(now_unix_time - nearest_unix_time) < 1e-4) { - gnss_sat_clock_.at(spacecraft_id) = gnss_sat_clock_table_.at(spacecraft_id).at(index); + gnss_sat_clock_.at(gnss_satellite_id) = gnss_sat_clock_table_.at(gnss_satellite_id).at(index); } else { - gnss_sat_clock_.at(spacecraft_id) = LagrangeInterpolation(time_period_.at(spacecraft_id), clock_bias_.at(spacecraft_id), now_unix_time); + gnss_sat_clock_.at(gnss_satellite_id) = + LagrangeInterpolation(time_period_.at(gnss_satellite_id), clock_bias_.at(gnss_satellite_id), now_unix_time); } } } -double GnssSat_clock::GetSatClock(int spacecraft_id) const { - if (spacecraft_id >= all_sat_num_) return 0.0; - return gnss_sat_clock_.at(spacecraft_id); +double GnssSat_clock::GetSatClock(int gnss_satellite_id) const { + if (gnss_satellite_id >= all_sat_num_) return 0.0; + return gnss_sat_clock_.at(gnss_satellite_id); } GnssSat_Info::GnssSat_Info() {} @@ -812,8 +817,8 @@ int GnssSat_Info::GetNumOfSatellites() const { } } -bool GnssSat_Info::GetWhetherValid(int spacecraft_id) const { - if (position_.GetWhetherValid(spacecraft_id) && clock_.GetWhetherValid(spacecraft_id)) return true; +bool GnssSat_Info::GetWhetherValid(int gnss_satellite_id) const { + if (position_.GetWhetherValid(gnss_satellite_id) && clock_.GetWhetherValid(gnss_satellite_id)) return true; return false; } @@ -821,11 +826,11 @@ const GnssSat_position& GnssSat_Info::GetGnssSatPos() const { return position_; const GnssSat_clock& GnssSat_Info::GetGnssSatClock() const { return clock_; } -libra::Vector<3> GnssSat_Info::GetSatellitePositionEcef(int spacecraft_id) const { return position_.GetSatEcef(spacecraft_id); } +libra::Vector<3> GnssSat_Info::GetSatellitePositionEcef(int gnss_satellite_id) const { return position_.GetSatEcef(gnss_satellite_id); } -libra::Vector<3> GnssSat_Info::GetSatellitePositionEci(int spacecraft_id) const { return position_.GetSatEci(spacecraft_id); } +libra::Vector<3> GnssSat_Info::GetSatellitePositionEci(int gnss_satellite_id) const { return position_.GetSatEci(gnss_satellite_id); } -double GnssSat_Info::GetSatelliteClock(int spacecraft_id) const { return clock_.GetSatClock(spacecraft_id); } +double GnssSat_Info::GetSatelliteClock(int gnss_satellite_id) const { return clock_.GetSatClock(gnss_satellite_id); } GnssSatellites::GnssSatellites(bool is_calc_enabled) #ifdef GNSS_SATELLITES_DEBUG_OUTPUT @@ -904,10 +909,10 @@ string GnssSatellites::GetIDFromIndex(int index) const { return estimate_info_.G int GnssSatellites::GetIndexFromID(string sat_num) const { return estimate_info_.GetGnssSatPos().GetIndexFromID(sat_num); } -bool GnssSatellites::GetWhetherValid(int spacecraft_id) const { - if (spacecraft_id >= GetNumOfSatellites()) return false; +bool GnssSatellites::GetWhetherValid(int gnss_satellite_id) const { + if (gnss_satellite_id >= GetNumOfSatellites()) return false; - if (true_info_.GetWhetherValid(spacecraft_id) && estimate_info_.GetWhetherValid(spacecraft_id)) + if (true_info_.GetWhetherValid(gnss_satellite_id) && estimate_info_.GetWhetherValid(gnss_satellite_id)) return true; else return false; @@ -919,95 +924,96 @@ const GnssSat_Info& GnssSatellites::Get_true_info() const { return true_info_; } const GnssSat_Info& GnssSatellites::Get_estimate_info() const { return estimate_info_; } -libra::Vector<3> GnssSatellites::GetSatellitePositionEcef(const int spacecraft_id) const { - // spacecraft_id is wrong or not valid - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { +libra::Vector<3> GnssSatellites::GetSatellitePositionEcef(const int gnss_satellite_id) const { + // gnss_satellite_id is wrong or not valid + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) { libra::Vector<3> res(0); return res; } - return estimate_info_.GetSatellitePositionEcef(spacecraft_id); + return estimate_info_.GetSatellitePositionEcef(gnss_satellite_id); } -libra::Vector<3> GnssSatellites::GetSatellitePositionEci(const int spacecraft_id) const { - // spacecraft_id is wrong or not valid - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { +libra::Vector<3> GnssSatellites::GetSatellitePositionEci(const int gnss_satellite_id) const { + // gnss_satellite_id is wrong or not valid + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) { libra::Vector<3> res(0); return res; } - return estimate_info_.GetSatellitePositionEci(spacecraft_id); + return estimate_info_.GetSatellitePositionEci(gnss_satellite_id); } -double GnssSatellites::GetSatelliteClock(const int spacecraft_id) const { - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) { +double GnssSatellites::GetSatelliteClock(const int gnss_satellite_id) const { + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) { return 0.0; } - return estimate_info_.GetSatelliteClock(spacecraft_id); + return estimate_info_.GetSatelliteClock(gnss_satellite_id); } -double GnssSatellites::GetPseudoRangeECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // spacecraft_id is wrong or not validate - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; +double GnssSatellites::GetPseudoRangeECEF(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, + const double frequency) const { + // gnss_satellite_id is wrong or not validate + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return 0.0; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); + auto gnss_position = true_info_.GetSatellitePositionEcef(gnss_satellite_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); + res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECEF); res += ionospheric_delay; return res; } -double GnssSatellites::GetPseudoRangeECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // spacecraft_id is wrong or not validate - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; +double GnssSatellites::GetPseudoRangeECI(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { + // gnss_satellite_id is wrong or not validate + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return 0.0; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); + auto gnss_position = true_info_.GetSatellitePositionEci(gnss_satellite_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); + res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECI); res += ionospheric_delay; return res; } -pair GnssSatellites::GetCarrierPhaseECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, +pair GnssSatellites::GetCarrierPhaseECEF(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // spacecraft_id is wrong or not validate - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return {0.0, 0.0}; + // gnss_satellite_id is wrong or not validate + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return {0.0, 0.0}; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); + auto gnss_position = true_info_.GetSatellitePositionEcef(gnss_satellite_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); + res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECEF); res -= ionospheric_delay; @@ -1021,23 +1027,23 @@ pair GnssSatellites::GetCarrierPhaseECEF(const int spacecraft_id return {cycle, bias}; } -pair GnssSatellites::GetCarrierPhaseECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, +pair GnssSatellites::GetCarrierPhaseECI(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const { - // spacecraft_id is wrong or not validate - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return {0.0, 0.0}; + // gnss_satellite_id is wrong or not validate + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return {0.0, 0.0}; double res = 0.0; - auto gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); + auto gnss_position = true_info_.GetSatellitePositionEci(gnss_satellite_id); for (int i = 0; i < 3; ++i) { res += pow(rec_position(i) - gnss_position(i), 2.0); } res = sqrt(res); // clock bias - res += rec_clock - true_info_.GetSatelliteClock(spacecraft_id); + res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(spacecraft_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECI); res -= ionospheric_delay; @@ -1052,10 +1058,10 @@ pair GnssSatellites::GetCarrierPhaseECI(const int spacecraft_id, } // for Ionospheric delay I[m] -double GnssSatellites::AddIonosphericDelay(const int spacecraft_id, const libra::Vector<3> rec_position, const double frequency, +double GnssSatellites::AddIonosphericDelay(const int gnss_satellite_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const { - // spacecraft_id is wrong or not validate - if (spacecraft_id >= GetNumOfSatellites() || !GetWhetherValid(spacecraft_id)) return 0.0; + // gnss_satellite_id is wrong or not validate + if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return 0.0; const double Earth_hemisphere = 6378.1; //[km] FIXME: Use constants.hpp @@ -1067,9 +1073,9 @@ double GnssSatellites::AddIonosphericDelay(const int spacecraft_id, const libra: libra::Vector<3> gnss_position; if (flag == ECEF) - gnss_position = true_info_.GetSatellitePositionEcef(spacecraft_id); + gnss_position = true_info_.GetSatellitePositionEcef(gnss_satellite_id); else if (flag == ECI) - gnss_position = true_info_.GetSatellitePositionEci(spacecraft_id); + gnss_position = true_info_.GetSatellitePositionEci(gnss_satellite_id); double angle_rad = CalcAngleTwoVectors_rad(rec_position, gnss_position - rec_position); const double default_delay = 20.0; //[m] default delay @@ -1096,13 +1102,13 @@ std::string GnssSatellites::GetLogValue() const { void GnssSatellites::DebugOutput() { #ifdef GNSS_SATELLITES_DEBUG_OUTPUT - for (int spacecraft_id = 0; spacecraft_id < gps_sat_num_; ++spacecraft_id) { - if (true_info_.GetWhetherValid(spacecraft_id)) { - auto true_pos = true_info_.GetSatellitePositionEcef(spacecraft_id); + for (int gnss_satellite_id = 0; gnss_satellite_id < gps_sat_num_; ++gnss_satellite_id) { + if (true_info_.GetWhetherValid(gnss_satellite_id)) { + auto true_pos = true_info_.GetSatellitePositionEcef(gnss_satellite_id); for (int i = 0; i < 3; ++i) { ofs_true << fixed << setprecision(10) << true_pos[i] << ","; } - auto true_clock = true_info_.GetSatelliteClock(spacecraft_id); + auto true_clock = true_info_.GetSatelliteClock(gnss_satellite_id); ofs_true << true_clock << ","; } else { for (int i = 0; i < 4; ++i) { @@ -1110,12 +1116,12 @@ void GnssSatellites::DebugOutput() { } } - if (estimate_info_.GetWhetherValid(spacecraft_id)) { - auto esti_pos = estimate_info_.GetSatellitePositionEcef(spacecraft_id); + if (estimate_info_.GetWhetherValid(gnss_satellite_id)) { + auto esti_pos = estimate_info_.GetSatellitePositionEcef(gnss_satellite_id); for (int i = 0; i < 3; ++i) { ofs_esti << fixed << setprecision(10) << esti_pos[i] << ","; } - auto esti_clock = estimate_info_.GetSatelliteClock(spacecraft_id); + auto esti_clock = estimate_info_.GetSatelliteClock(gnss_satellite_id); ofs_esti << esti_clock << ","; } else { for (int i = 0; i < 4; ++i) { @@ -1123,11 +1129,11 @@ void GnssSatellites::DebugOutput() { } } - if (GetWhetherValid(spacecraft_id)) { - auto true_pos = true_info_.GetSatellitePositionEcef(spacecraft_id); - auto true_clock = true_info_.GetSatelliteClock(spacecraft_id); - auto esti_pos = estimate_info_.GetSatellitePositionEcef(spacecraft_id); - auto esti_clock = estimate_info_.GetSatelliteClock(spacecraft_id); + if (GetWhetherValid(gnss_satellite_id)) { + auto true_pos = true_info_.GetSatellitePositionEcef(gnss_satellite_id); + auto true_clock = true_info_.GetSatelliteClock(gnss_satellite_id); + auto esti_pos = estimate_info_.GetSatellitePositionEcef(gnss_satellite_id); + auto esti_clock = estimate_info_.GetSatelliteClock(gnss_satellite_id); for (int i = 0; i < 3; ++i) { ofs_sa << fixed << setprecision(10) << esti_pos[i] - true_pos[i] << ","; diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 200bdcefb..8bf65f268 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -76,9 +76,9 @@ class GnssSat_coordinate { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available - * @param [in] spacecraft_id: Index of GNSS satellite + * @param [in] gnss_satellite_id: Index of GNSS satellite */ - bool GetWhetherValid(int spacecraft_id) const; + bool GetWhetherValid(int gnss_satellite_id) const; protected: /** @@ -156,15 +156,15 @@ class GnssSat_position : public GnssSat_coordinate { /** * @fn GetSatEcef * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatEcef(int spacecraft_id) const; + libra::Vector<3> GetSatEcef(int gnss_satellite_id) const; /** * @fn GetSatEci * @brief Return GNSS satellite position vector in the ECI frame [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatEci(int spacecraft_id) const; + libra::Vector<3> GetSatEci(int gnss_satellite_id) const; private: std::vector> gnss_sat_ecef_; //!< List of GNSS satellite position at specific time in the ECEF frame [m] @@ -214,9 +214,9 @@ class GnssSat_clock : public GnssSat_coordinate { /** * @fn GetSatClock * @brief Return GNSS satellite clock in distance expression [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - double GetSatClock(int spacecraft_id) const; + double GetSatClock(int gnss_satellite_id) const; private: std::vector gnss_sat_clock_; //!< List of clock bias of all GNSS satellites at specific time expressed in distance [m] @@ -273,27 +273,27 @@ class GnssSat_Info { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available for both position and clock information - * @param [in] spacecraft_id: Index of GNSS satellite + * @param [in] gnss_satellite_id: Index of GNSS satellite */ - bool GetWhetherValid(int spacecraft_id) const; + bool GetWhetherValid(int gnss_satellite_id) const; /** * @fn GetSatellitePositionEcef * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatellitePositionEcef(int spacecraft_id) const; + libra::Vector<3> GetSatellitePositionEcef(int gnss_satellite_id) const; /** * @fn GetSatellitePositionEci * @brief Return GNSS satellite position vector in the ECEF frame [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - libra::Vector<3> GetSatellitePositionEci(int spacecraft_id) const; + libra::Vector<3> GetSatellitePositionEci(int gnss_satellite_id) const; /** * @fn GetSatelliteClock * @brief Return GNSS satellite clock in distance expression [m] - * @param [in] spacecraft_id: GNSS satellite ID defined in this class + * @param [in] gnss_satellite_id: GNSS satellite ID defined in this class */ - double GetSatelliteClock(int spacecraft_id) const; + double GetSatelliteClock(int gnss_satellite_id) const; /** * @fn GetGnssSatPos * @brief Return GNSS satellite position information class @@ -381,9 +381,9 @@ class GnssSatellites : public ILoggable { /** * @fn GetWhetherValid * @brief Return true the GNSS satellite information is available for both position and clock for both true and estimated value - * @param [in] spacecraft_id: Index of GNSS satellite + * @param [in] gnss_satellite_id: Index of GNSS satellite */ - bool GetWhetherValid(int spacecraft_id) const; + bool GetWhetherValid(int gnss_satellite_id) const; /** * @fn GetStartUnixTime * @brief Return start unix time @@ -403,63 +403,63 @@ class GnssSatellites : public ILoggable { /** * @fn GetSatellitePositionEcef * @brief Return GNSS satellite position in the ECEF frame [m] - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID */ - libra::Vector<3> GetSatellitePositionEcef(const int spacecraft_id) const; + libra::Vector<3> GetSatellitePositionEcef(const int gnss_satellite_id) const; /** * @fn GetSatellitePositionEci * @brief Return GNSS satellite position in the ECI frame [m] - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID */ - libra::Vector<3> GetSatellitePositionEci(const int spacecraft_id) const; + libra::Vector<3> GetSatellitePositionEci(const int gnss_satellite_id) const; /** * @fn GetSatelliteClock * @brief Return GNSS satellite clock - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID */ - double GetSatelliteClock(const int spacecraft_id) const; + double GetSatelliteClock(const int gnss_satellite_id) const; /** * @fn GetPseudoRangeECEF * @brief Calculate pseudo range between receiver and a GNSS satellite - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECEF frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Pseudo range [m] */ - double GetPseudoRangeECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + double GetPseudoRangeECEF(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; /** * @fn GetPseudoRangeECI * @brief Calculate pseudo range between receiver and a GNSS satellite - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECI frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Pseudo range [m] */ - double GetPseudoRangeECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; + double GetPseudoRangeECI(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; /** * @fn GetCarrierPhaseECEF * @brief Calculate carrier phase observed by a receiver for a GNSS satellite - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECEF frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Carrier phase cycle and bias [-] */ - std::pair GetCarrierPhaseECEF(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, + std::pair GetCarrierPhaseECEF(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; /** * @fn GetCarrierPhaseECI * @brief Calculate carrier phase observed by a receiver for a GNSS satellite - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID * @param [in] rec_position: Receiver position vector in the ECI frame [m] * @param [in] rec_clock: Receiver clock * @param [in] frequency: Frequency of the signal [MHz] * @return Carrier phase cycle and bias [-] */ - std::pair GetCarrierPhaseECI(const int spacecraft_id, libra::Vector<3> rec_position, double rec_clock, + std::pair GetCarrierPhaseECI(const int gnss_satellite_id, libra::Vector<3> rec_position, double rec_clock, const double frequency) const; // Override ILoggable @@ -491,13 +491,13 @@ class GnssSatellites : public ILoggable { * @fn AddIonosphericDelay * @brief Calculation of ionospheric delay * @note TODO: Ionospheric delay very Miscellaneous need to fix - * @param [in] spacecraft_id: GNSS satellite ID + * @param [in] gnss_satellite_id: GNSS satellite ID * @param [in] rec_position: Receiver position [m] * @param [in] frequency: Frequency [MHz] * @param [in] flag: The frame definition of the receiver position (ECI or ECEF) * @return Ionospheric delay [m] */ - double AddIonosphericDelay(const int spacecraft_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const; + double AddIonosphericDelay(const int gnss_satellite_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const; bool is_calc_enabled_ = true; //!< Flag to manage the GNSS satellite position calculation GnssSat_Info true_info_; //!< True information of GNSS satellites From 1de39ef6d6c01d36e233a5f21795f54dcd210d96 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 20:48:19 +0100 Subject: [PATCH 0932/1086] Fix Initialize name --- .../initialize_monte_carlo_simulation.cpp | 2 +- .../initialize_monte_carlo_simulation.hpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 32f675074..89618aa86 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -10,7 +10,7 @@ #define MAX_CHAR_NUM 256 -MonteCarloSimulationExecutor* InitMCSim(std::string file_name) { +MonteCarloSimulationExecutor* InitMonteCarloSimulation(std::string file_name) { IniAccess ini_file(file_name); const char* section = "MONTE_CARLO_EXECUTION"; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp index 8a571fc63..e4dcd60a2 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.hpp @@ -10,9 +10,9 @@ #include "monte_carlo_simulation_executor.hpp" /** - * @fn InitMCSim + * @fn InitMonteCarloSimulation * @brief Initialize function for Monte-Carlo Simulator */ -MonteCarloSimulationExecutor* InitMCSim(std::string file_name); +MonteCarloSimulationExecutor* InitMonteCarloSimulation(std::string file_name); #endif // S2E_SIMULATION_MONTE_CARLO_SIMULATION_INITIALIZE_MONTE_CARLO_SIMULATION_HPP_ From fa2c19e7ce35da403f998734f839cec07dae8519 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 20:49:31 +0100 Subject: [PATCH 0933/1086] Fix typo --- .../monte_carlo_simulation/simulation_object.cpp | 12 ++++++------ .../monte_carlo_simulation/simulation_object.hpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/simulation_object.cpp b/src/simulation/monte_carlo_simulation/simulation_object.cpp index 0fc796262..eb0273eaa 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.cpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.cpp @@ -5,15 +5,15 @@ #include "simulation_object.hpp" -std::map SimulationObject::ojbect_list_; +std::map SimulationObject::object_list_; SimulationObject::SimulationObject(std::string name) : name_(name) { // Check the name is already registered in so_list - std::map::iterator itr = SimulationObject::ojbect_list_.find(name); + std::map::iterator itr = SimulationObject::object_list_.find(name); - if (itr == SimulationObject::ojbect_list_.end()) { + if (itr == SimulationObject::object_list_.end()) { // Register itself in so_list if it is not registered yet - SimulationObject::ojbect_list_[name] = this; + SimulationObject::object_list_[name] = this; } else { // If it is already registered in so_list, throw error. It should be deleted in the finalize phase of previous case. // Or there is a possibility that the same name SimulationObjects are registered in the list. @@ -23,11 +23,11 @@ SimulationObject::SimulationObject(std::string name) : name_(name) { SimulationObject::~SimulationObject() { // Remove itself from so_list - SimulationObject::ojbect_list_.erase(name_); + SimulationObject::object_list_.erase(name_); } void SimulationObject::SetAllParameters(const MonteCarloSimulationExecutor& monte_carlo_simulator) { - for (auto so : SimulationObject::ojbect_list_) { + for (auto so : SimulationObject::object_list_) { so.second->SetParameters(monte_carlo_simulator); } } diff --git a/src/simulation/monte_carlo_simulation/simulation_object.hpp b/src/simulation/monte_carlo_simulation/simulation_object.hpp index 87afe112b..9d46d482d 100644 --- a/src/simulation/monte_carlo_simulation/simulation_object.hpp +++ b/src/simulation/monte_carlo_simulation/simulation_object.hpp @@ -70,7 +70,7 @@ class SimulationObject { private: std::string name_; //!< Name to distinguish the target variable in initialize file for Monte-Carlo simulation - static std::map ojbect_list_; //!< list of objects with simulation parameters + static std::map object_list_; //!< list of objects with simulation parameters }; /** From 705dcab54e15de0377b2d226bef9716ff6c82ae2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:09:47 +0100 Subject: [PATCH 0934/1086] Fix public function name --- src/components/ideal/torque_generator.hpp | 4 +-- src/components/real/aocs/gyro_sensor.cpp | 2 +- src/components/real/aocs/star_sensor.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 28 +++++++++---------- src/dynamics/dynamics.cpp | 2 +- src/environment/local/local_environment.cpp | 2 +- src/simulation/case/sample_case.cpp | 2 +- .../sample_spacecraft/sample_components.cpp | 4 +-- 8 files changed, 23 insertions(+), 23 deletions(-) diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index db75006ad..e7fc46cd6 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -68,10 +68,10 @@ class TorqueGenerator : public Component, public ILoggable { // Setter /** - * @fn SetTorque_b_Nm + * @fn SetTorque_b_Nm_Nm * @brief Set ordered torque in the body fixed frame [Nm] */ - inline void SetTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { ordered_torque_b_Nm_ = torque_b_Nm; }; + inline void SetTorque_b_Nm_Nm(const libra::Vector<3> torque_b_Nm) { ordered_torque_b_Nm_ = torque_b_Nm; }; protected: libra::Vector<3> ordered_torque_b_Nm_{0.0}; //!< Ordered torque in the body fixed frame [Nm] diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index cf5d2659e..e9eec6c4e 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -22,7 +22,7 @@ GyroSensor::~GyroSensor() {} void GyroSensor::MainRoutine(const int time_count) { UNUSED(time_count); - angular_velocity_c_rad_s_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetOmega_b()); // Convert frame + angular_velocity_c_rad_s_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetAngularVelocity_b_rad_s()); // Convert frame angular_velocity_c_rad_s_ = Measure(angular_velocity_c_rad_s_); // Add noises } diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index 66b532a48..eaa4613e4 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -129,7 +129,7 @@ void StarSensor::AllJudgement(const LocalCelestialInformation* local_celestial_i judgement = SunJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("SUN")); judgement += EarthJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("EARTH")); judgement += MoonJudgement(local_celestial_information->GetPositionFromSpacecraft_b_m("MOON")); - judgement += CaptureRateJudgement(attitude->GetOmega_b()); + judgement += CaptureRateJudgement(attitude->GetAngularVelocity_b_rad_s()); if (judgement > 0) error_flag_ = true; else diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 8019ca4a1..d57f7886d 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -32,30 +32,30 @@ class Attitude : public ILoggable, public SimulationObject { // Getter /** - * @fn GetPropStep + * @fn GetPropStep_s * @brief Return propagation step [sec] */ - inline double GetPropStep() const { return propagation_step_s_; } + inline double GetPropStep_s() const { return propagation_step_s_; } /** - * @fn GetOmega_b + * @fn GetAngularVelocity_b_rad_s * @brief Return angular velocity of spacecraft body-fixed frame with respect to the inertial frame [rad/s] */ - inline libra::Vector<3> GetOmega_b() const { return angular_velocity_b_rad_s_; } + inline libra::Vector<3> GetAngularVelocity_b_rad_s() const { return angular_velocity_b_rad_s_; } /** * @fn GetQuaternion_i2b * @brief Return attitude quaternion from the inertial frame to the body fixed frame */ inline libra::Quaternion GetQuaternion_i2b() const { return quaternion_i2b_; } /** - * @fn GetTotalAngMomNorm + * @fn GetTotalAngularMomentNorm_Nms * @brief Return norm of total angular momentum of the spacecraft [Nms] */ - inline double GetTotalAngMomNorm() const { return libra::CalcNorm(angular_momentum_total_b_Nms_); } + inline double GetTotalAngularMomentNorm_Nms() const { return libra::CalcNorm(angular_momentum_total_b_Nms_); } /** - * @fn GetEnergy + * @fn GetKineticEnergy_J * @brief Return rotational Kinetic Energy of Spacecraft [J] */ - inline double GetEnergy() const { return kinetic_energy_J_; } + inline double GetKineticEnergy_J() const { return kinetic_energy_J_; } /** * @fn GetInertiaTensor_b_kgm2 * @brief Return inertia tensor [kg m^2] @@ -64,30 +64,30 @@ class Attitude : public ILoggable, public SimulationObject { // Setter /** - * @fn SetOmega_b + * @fn SetAngularVelocity_b_rad_s * @brief Set angular velocity of the body fixed frame with respect to the inertial frame [rad/s] */ - inline void SetOmega_b(const libra::Vector<3> omega_b_rad_s) { angular_velocity_b_rad_s_ = omega_b_rad_s; } + inline void SetAngularVelocity_b_rad_s(const libra::Vector<3> angular_velocity_b_rad_s) { angular_velocity_b_rad_s_ = angular_velocity_b_rad_s; } /** * @fn SetQuaternion_i2b * @brief Set attitude quaternion from the inertial frame to the body frame */ inline void SetQuaternion_i2b(const libra::Quaternion quaternion_i2b) { quaternion_i2b_ = quaternion_i2b; } /** - * @fn SetTorque_b + * @fn SetTorque_b_Nm * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] */ - inline void SetTorque_b(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ = torque_b_Nm; } + inline void SetTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ = torque_b_Nm; } /** * @fn AddTorque_b_Nm * @brief Add torque acting on the spacecraft on the body fixed frame [Nm] */ inline void AddTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ += torque_b_Nm; } /** - * @fn SetAngMom_rw + * @fn SetRwAngularMomentum_b_Nms * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] */ - inline void SetAngMom_rw(const libra::Vector<3> angular_momentum_rw_b_Nms) { angular_momentum_reaction_wheel_b_Nms_ = angular_momentum_rw_b_Nms; } + inline void SetRwAngularMomentum_b_Nms(const libra::Vector<3> angular_momentum_rw_b_Nms) { angular_momentum_reaction_wheel_b_Nms_ = angular_momentum_rw_b_Nms; } /** * @fn Propagate diff --git a/src/dynamics/dynamics.cpp b/src/dynamics/dynamics.cpp index a9cf3de49..203354090 100644 --- a/src/dynamics/dynamics.cpp +++ b/src/dynamics/dynamics.cpp @@ -60,7 +60,7 @@ void Dynamics::Update(const SimulationTime* simulation_time, const LocalCelestia void Dynamics::ClearForceTorque(void) { libra::Vector<3> zero(0.0); - attitude_->SetTorque_b(zero); + attitude_->SetTorque_b_Nm(zero); orbit_->SetAcceleration_i_m_s2(zero); } diff --git a/src/environment/local/local_environment.cpp b/src/environment/local/local_environment.cpp index 2fb3cac22..8478cfb77 100644 --- a/src/environment/local/local_environment.cpp +++ b/src/environment/local/local_environment.cpp @@ -55,7 +55,7 @@ void LocalEnvironment::Update(const Dynamics* dynamics, const SimulationTime* si // Update local environments that depend on the attitude (and the position) if (simulation_time->GetAttitudePropagateFlag()) { celestial_information_->UpdateAllObjectsInformation(orbit.GetPosition_i_m(), orbit.GetVelocity_i_m_s(), attitude.GetQuaternion_i2b(), - attitude.GetOmega_b()); + attitude.GetAngularVelocity_b_rad_s()); geomagnetic_field_->CalcMagneticField(simulation_time->GetCurrentDecimalYear(), simulation_time->GetCurrentSiderealTime(), orbit.GetGeodeticPosition(), attitude.GetQuaternion_i2b()); } diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index fb95f084a..6a6fa6acd 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -75,7 +75,7 @@ string SampleCase::GetLogValue() const { // auto pos_i = sample_sat->dynamics_->GetOrbit().GetPosition_i_m(); // auto vel_i = sample_sat->dynamics_->GetOrbit().GetVelocity_i_m_s(); // auto quat_i2b = sample_sat->dynamics_->GetAttitude().GetQuaternion_i2b(); - // auto omega_b = sample_sat->dynamics_->GetAttitude().GetOmega_b(); + // auto omega_b = sample_sat->dynamics_->GetAttitude().GetAngularVelocity_b_rad_s(); // Need to match the contents of log with header setting above str_tmp += WriteScalar(global_environment_->GetSimulationTime().GetElapsedTime_s()); diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 4bce66337..15a698e97 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -70,7 +70,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // RW file_name = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); configuration_->main_logger_->CopyFileToLogDirectory(file_name); - reaction_wheel_ = new ReactionWheel(InitReactionWheel(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep(), + reaction_wheel_ = new ReactionWheel(InitReactionWheel(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep_s(), global_environment_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator @@ -132,7 +132,7 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // torque_Nm[0] = 1.0; // torque_Nm[1] = 0.0; // torque_Nm[2] = 0.0; - // torque_generator_->SetTorque_b_Nm(torque_Nm); + // torque_generator_->SetTorque_b_Nm_Nm(torque_Nm); } SampleComponents::~SampleComponents() { From f1ac87e0774fee79cc4c200b923a9782fddee684 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:20:55 +0100 Subject: [PATCH 0935/1086] Fix format --- src/dynamics/attitude/attitude.hpp | 8 ++++++-- .../spacecraft/sample_spacecraft/sample_components.cpp | 5 +++-- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index d57f7886d..355f9db8a 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -74,7 +74,9 @@ class Attitude : public ILoggable, public SimulationObject { */ inline void SetQuaternion_i2b(const libra::Quaternion quaternion_i2b) { quaternion_i2b_ = quaternion_i2b; } /** - * @fn SetTorque_b_Nm + * @brief + * + */ * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] */ inline void SetTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ = torque_b_Nm; } @@ -87,7 +89,9 @@ class Attitude : public ILoggable, public SimulationObject { * @fn SetRwAngularMomentum_b_Nms * @brief Set angular momentum of reaction wheel in the body fixed frame [Nms] */ - inline void SetRwAngularMomentum_b_Nms(const libra::Vector<3> angular_momentum_rw_b_Nms) { angular_momentum_reaction_wheel_b_Nms_ = angular_momentum_rw_b_Nms; } + inline void SetRwAngularMomentum_b_Nms(const libra::Vector<3> angular_momentum_rw_b_Nms) { + angular_momentum_reaction_wheel_b_Nms_ = angular_momentum_rw_b_Nms; + } /** * @fn Propagate diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp index 15a698e97..113467534 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp @@ -70,8 +70,9 @@ SampleComponents::SampleComponents(const Dynamics* dynamics, Structure* structur // RW file_name = iniAccess.ReadString("COMPONENT_FILES", "rw_file"); configuration_->main_logger_->CopyFileToLogDirectory(file_name); - reaction_wheel_ = new ReactionWheel(InitReactionWheel(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep_s(), - global_environment_->GetSimulationTime().GetComponentStepTime_s())); + reaction_wheel_ = + new ReactionWheel(InitReactionWheel(clock_generator, pcu_->GetPowerPort(2), 1, file_name, dynamics_->GetAttitude().GetPropStep_s(), + global_environment_->GetSimulationTime().GetComponentStepTime_s())); // Torque Generator file_name = iniAccess.ReadString("COMPONENT_FILES", "torque_generator_file"); From c10d3512b5e264374fa7a01845e66a520b97edff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:23:35 +0100 Subject: [PATCH 0936/1086] Fix typo --- src/dynamics/attitude/attitude.hpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 355f9db8a..570e3918a 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -74,9 +74,7 @@ class Attitude : public ILoggable, public SimulationObject { */ inline void SetQuaternion_i2b(const libra::Quaternion quaternion_i2b) { quaternion_i2b_ = quaternion_i2b; } /** - * @brief - * - */ + * @fn SetTorque_b_Nm * @brief Set torque acting on the spacecraft on the body fixed frame [Nm] */ inline void SetTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { torque_b_Nm_ = torque_b_Nm; } From 5138aafd20b52d94a37c65afe550261bf88d925b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:37:16 +0100 Subject: [PATCH 0937/1086] Fix enum for GNSS and Simulation Mode --- src/components/base/i2c_controller.cpp | 10 ++--- src/components/base/i2c_controller.hpp | 2 +- .../i2c_target_communication_with_obc.cpp | 44 +++++++++---------- .../i2c_target_communication_with_obc.hpp | 2 +- .../base/uart_communication_with_obc.cpp | 44 +++++++++---------- .../base/uart_communication_with_obc.hpp | 12 ++--- src/components/real/aocs/gnss_receiver.cpp | 4 +- src/components/real/aocs/gnss_receiver.hpp | 6 +-- .../real/aocs/initialize_gnss_receiver.cpp | 24 +++++----- 9 files changed, 74 insertions(+), 74 deletions(-) diff --git a/src/components/base/i2c_controller.cpp b/src/components/base/i2c_controller.cpp index 2b3c47037..d191da728 100644 --- a/src/components/base/i2c_controller.cpp +++ b/src/components/base/i2c_controller.cpp @@ -14,19 +14,19 @@ I2cController::I2cController(const unsigned int hils_port_id, const unsigned int rx_buffer_size_(rx_buffer_size), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; int ret = hils_port_manager_->I2cControllerConnectComPort(hils_port_id_, baud_rate_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Error: I2cCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:OFF Check compo initialization"); #endif } I2cController::~I2cController() { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return; + if (simulation_mode_ != SimulationMode::kHils) return; int ret = hils_port_manager_->I2cControllerCloseComPort(hils_port_id_); if (ret != 0) { @@ -35,11 +35,11 @@ I2cController::~I2cController() { } int I2cController::ReceiveTelemetry(const unsigned char length) { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; return hils_port_manager_->I2cControllerReceive(hils_port_id_, &rx_buffer_.front(), 0, length); } int I2cController::SendCommand(const unsigned char length) { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; return hils_port_manager_->I2cControllerSend(hils_port_id_, &tx_buffer_.front(), 0, length); } diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index 7475b91db..a75c9545e 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -59,7 +59,7 @@ class I2cController { unsigned int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 unsigned int tx_buffer_size_; //!< TX (Controller to Target) buffer size unsigned int rx_buffer_size_; //!< RX (Target to Controller) buffer size - OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode (SILS or HILS) + SimulationMode simulation_mode_ = SimulationMode::kError; //!< Simulation mode (SILS or HILS) HilsPortManager* hils_port_manager_; //!< HILS port manager }; diff --git a/src/components/base/i2c_target_communication_with_obc.cpp b/src/components/base/i2c_target_communication_with_obc.cpp index b3938f75c..a4b7cc4fe 100644 --- a/src/components/base/i2c_target_communication_with_obc.cpp +++ b/src/components/base/i2c_target_communication_with_obc.cpp @@ -9,10 +9,10 @@ I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int sils_port_id, const unsigned char i2c_address, OnBoardComputer* obc) : sils_port_id_(sils_port_id), i2c_address_(i2c_address), obc_(obc) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - simulation_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = SimulationMode::kSils; obc_->I2cConnectPort(sils_port_id_, i2c_address_); #endif } @@ -21,13 +21,13 @@ I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), i2c_address_(i2c_address), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; int ret = hils_port_manager_->I2cTargetConnectComPort(hils_port_id_); if (ret != 0) { std::cout << "Error: ObcI2cTargetCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif } @@ -37,13 +37,13 @@ I2cTargetCommunicationWithObc::I2cTargetCommunicationWithObc(const unsigned int HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), i2c_address_(i2c_address), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; int ret = hils_port_manager_->I2cTargetConnectComPort(hils_port_id_); if (ret != 0) { std::cout << "Error: ObcI2cTargetCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; } #else - simulation_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = SimulationMode::kSils; obc_->I2cConnectPort(sils_port_id_, i2c_address_); #endif } @@ -65,9 +65,9 @@ I2cTargetCommunicationWithObc::~I2cTargetCommunicationWithObc() { int ret; switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: ret = obc_->I2cCloseComPort(sils_port_id_); if (ret != 0) { // TODO: Add a flag to select whether to show or hide warnings @@ -75,7 +75,7 @@ I2cTargetCommunicationWithObc::~I2cTargetCommunicationWithObc() { // "CloseComPort ID:" << sils_port_id_ << "\n"; } break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: ret = hils_port_manager_->I2cTargetCloseComPort(hils_port_id_); if (ret != 0) { // TODO: Add a flag to select whether to show or hide warnings @@ -91,12 +91,12 @@ I2cTargetCommunicationWithObc::~I2cTargetCommunicationWithObc() { void I2cTargetCommunicationWithObc::ReadRegister(const unsigned char register_address, unsigned char* data, const unsigned char length) { switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: obc_->I2cComponentReadRegister(sils_port_id_, i2c_address_, register_address, data, length); break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: hils_port_manager_->I2cTargetReadRegister(hils_port_id_, register_address, data, length); break; default: @@ -107,12 +107,12 @@ void I2cTargetCommunicationWithObc::ReadRegister(const unsigned char register_ad void I2cTargetCommunicationWithObc::WriteRegister(const unsigned char register_address, const unsigned char* data, const unsigned char length) { switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: obc_->I2cComponentWriteRegister(sils_port_id_, i2c_address_, register_address, data, length); break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: hils_port_manager_->I2cTargetWriteRegister(hils_port_id_, register_address, data, length); break; default: @@ -123,12 +123,12 @@ void I2cTargetCommunicationWithObc::WriteRegister(const unsigned char register_a void I2cTargetCommunicationWithObc::ReadCommand(unsigned char* data, const unsigned char length) { switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: obc_->I2cComponentReadCommand(sils_port_id_, i2c_address_, data, length); break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: hils_port_manager_->I2cTargetReadCommand(hils_port_id_, data, length); break; default: @@ -138,22 +138,22 @@ void I2cTargetCommunicationWithObc::ReadCommand(unsigned char* data, const unsig } int I2cTargetCommunicationWithObc::ReceiveCommand() { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; return hils_port_manager_->I2cTargetReceive(hils_port_id_); } int I2cTargetCommunicationWithObc::SendTelemetry(const unsigned char length) { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; return hils_port_manager_->I2cTargetSend(hils_port_id_, length); } int I2cTargetCommunicationWithObc::GetStoredFrameCounter() { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; return hils_port_manager_->I2cTargetGetStoredFrameCounter(hils_port_id_); } int I2cTargetCommunicationWithObc::StoreTelemetry(const unsigned int stored_frame_num, const unsigned char tlm_size) { - if (simulation_mode_ != OBC_COM_UART_MODE::HILS) return -1; + if (simulation_mode_ != SimulationMode::kHils) return -1; int additional_frame_num = stored_frame_num - GetStoredFrameCounter(); if (additional_frame_num <= 0) return -1; diff --git a/src/components/base/i2c_target_communication_with_obc.hpp b/src/components/base/i2c_target_communication_with_obc.hpp index 4556e3c6c..12ff9a4ac 100644 --- a/src/components/base/i2c_target_communication_with_obc.hpp +++ b/src/components/base/i2c_target_communication_with_obc.hpp @@ -115,7 +115,7 @@ class I2cTargetCommunicationWithObc { unsigned char i2c_address_; //!< I2C address for the target bool is_moved_ = false; //!< Flag to show the object is copied or not - OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode + SimulationMode simulation_mode_ = SimulationMode::kError; //!< Simulation mode OnBoardComputer* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager diff --git a/src/components/base/uart_communication_with_obc.cpp b/src/components/base/uart_communication_with_obc.cpp index 365decfb1..37d3a976c 100644 --- a/src/components/base/uart_communication_with_obc.cpp +++ b/src/components/base/uart_communication_with_obc.cpp @@ -9,10 +9,10 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_id, OnBoardComputer* obc) : sils_port_id_(sils_port_id), obc_(obc) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - simulation_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = SimulationMode::kSils; #endif tx_buffer_size_ = kDefaultBufferSize; rx_buffer_size_ = kDefaultBufferSize; @@ -23,10 +23,10 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_ const unsigned int rx_buffer_size, OnBoardComputer* obc) : sils_port_id_(sils_port_id), tx_buffer_size_(tx_buffer_size), rx_buffer_size_(rx_buffer_size), obc_(obc) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:ON Check compo initialization\n"); #else - simulation_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = SimulationMode::kSils; #endif if (tx_buffer_size_ > kDefaultBufferSize) tx_buffer_size_ = kDefaultBufferSize; if (rx_buffer_size_ > kDefaultBufferSize) rx_buffer_size_ = kDefaultBufferSize; @@ -36,9 +36,9 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int sils_port_ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_id, const unsigned int baud_rate, HilsPortManager* hils_port_manager) : hils_port_id_(hils_port_id), baud_rate_(baud_rate), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; #else - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif tx_buffer_size_ = kDefaultBufferSize; @@ -54,9 +54,9 @@ UartCommunicationWithObc::UartCommunicationWithObc(const unsigned int hils_port_ rx_buffer_size_(rx_buffer_size), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; #else - simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; + simulation_mode_ = SimulationMode::kError; printf("Error: USE_HILS:OFF Check compo initialization\n"); #endif if (tx_buffer_size_ > kDefaultBufferSize) tx_buffer_size_ = kDefaultBufferSize; @@ -68,9 +68,9 @@ UartCommunicationWithObc::UartCommunicationWithObc(const int sils_port_id, OnBoa const unsigned int baud_rate, HilsPortManager* hils_port_manager) : sils_port_id_(sils_port_id), hils_port_id_(hils_port_id), baud_rate_(baud_rate), obc_(obc), hils_port_manager_(hils_port_manager) { #ifdef USE_HILS - simulation_mode_ = OBC_COM_UART_MODE::HILS; + simulation_mode_ = SimulationMode::kHils; #else - simulation_mode_ = OBC_COM_UART_MODE::SILS; + simulation_mode_ = SimulationMode::kSils; #endif tx_buffer_size_ = kDefaultBufferSize; rx_buffer_size_ = kDefaultBufferSize; @@ -81,16 +81,16 @@ UartCommunicationWithObc::~UartCommunicationWithObc() { if (is_connected_ == false) return; int ret; switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: std::cout << "Error: ObcCommunication CloseComPort MODE_ERROR\n"; break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: ret = obc_->CloseComPort(sils_port_id_); if (ret != 0) { std::cout << "Error: ObcCommunication CloseComPort ID:" << sils_port_id_ << "\n"; } break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: ret = hils_port_manager_->UartCloseComPort(hils_port_id_); if (ret != 0) { std::cout << "Error: ObcCommunication CloseComPort ID:" << hils_port_id_ << "\n"; @@ -105,9 +105,9 @@ UartCommunicationWithObc::~UartCommunicationWithObc() { void UartCommunicationWithObc::InitializeObcComBase() { int ret; switch (simulation_mode_) { - case OBC_COM_UART_MODE::MODE_ERROR: + case SimulationMode::kError: break; - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: ret = obc_->ConnectComPort(sils_port_id_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Already connected: ObcCommunication ConnectComPort ID:" << sils_port_id_ << "\n"; @@ -116,7 +116,7 @@ void UartCommunicationWithObc::InitializeObcComBase() { is_connected_ = true; } break; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: ret = hils_port_manager_->UartConnectComPort(hils_port_id_, baud_rate_, tx_buffer_size_, rx_buffer_size_); if (ret != 0) { std::cout << "Error: ObcCommunication ConnectComPort ID:" << hils_port_id_ << "\n"; @@ -132,18 +132,18 @@ void UartCommunicationWithObc::InitializeObcComBase() { } int UartCommunicationWithObc::ReceiveCommand(const unsigned int offset, const unsigned int rec_size) { - if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; + if (simulation_mode_ == SimulationMode::kError) return -1; if (offset > rx_buffer_size_) return -1; if (offset + rec_size > rx_buffer_size_) return -1; rx_buffer_.resize(rec_size); int ret; switch (simulation_mode_) { - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: ret = obc_->ReceivedByCompo(sils_port_id_, &rx_buffer_.front(), offset, rec_size); if (ret == 0) return 0; // No read data return ParseCommand(ret); - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: ret = hils_port_manager_->UartReceive(hils_port_id_, &rx_buffer_.front(), offset, rec_size); if (ret == 0) return 0; // No read data return ParseCommand(ret); @@ -154,16 +154,16 @@ int UartCommunicationWithObc::ReceiveCommand(const unsigned int offset, const un } } int UartCommunicationWithObc::SendTelemetry(const unsigned int offset) { - if (simulation_mode_ == OBC_COM_UART_MODE::MODE_ERROR) return -1; + if (simulation_mode_ == SimulationMode::kError) return -1; int tlm_size = GenerateTelemetry(); if (offset > rx_buffer_size_) return -1; if (offset + tlm_size > rx_buffer_size_) return -1; switch (simulation_mode_) { - case OBC_COM_UART_MODE::SILS: + case SimulationMode::kSils: obc_->SendFromCompo(sils_port_id_, &tx_buffer_.front(), offset, tlm_size); return 0; - case OBC_COM_UART_MODE::HILS: + case SimulationMode::kHils: hils_port_manager_->UartSend(hils_port_id_, &tx_buffer_.front(), offset, tlm_size); return 0; default: diff --git a/src/components/base/uart_communication_with_obc.hpp b/src/components/base/uart_communication_with_obc.hpp index 231c5f157..0db74815b 100644 --- a/src/components/base/uart_communication_with_obc.hpp +++ b/src/components/base/uart_communication_with_obc.hpp @@ -11,14 +11,14 @@ #include "../real/cdh/on_board_computer.hpp" /** - * @enum OBC_COM_UART_MODE + * @enum SimulationMode * @brief Simulation mode (SILS or HILS) * @details In the SILS mode, S2E does not need to communicate with OnBoardComputer in S2E */ -enum class OBC_COM_UART_MODE { - SILS, //!< Software In the Loop Simulation - HILS, //!< Hardware In the Loop Simulation - MODE_ERROR, //!< Error +enum class SimulationMode { + kSils, //!< Software In the Loop Simulation + kHils, //!< Hardware In the Loop Simulation + kError, //!< Error }; /** @@ -105,7 +105,7 @@ class UartCommunicationWithObc { unsigned int rx_buffer_size_; //!< RX (OBC to Component) buffer size bool is_connected_ = false; //!< Connection flag - OBC_COM_UART_MODE simulation_mode_ = OBC_COM_UART_MODE::MODE_ERROR; //!< Simulation mode + SimulationMode simulation_mode_ = SimulationMode::kError; //!< Simulation mode OnBoardComputer* obc_; //!< Communication target OBC HilsPortManager* hils_port_manager_; //!< HILS port manager diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index afb7d6996..9aa169718 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -72,9 +72,9 @@ void GnssReceiver::MainRoutine(const int time_count) { } void GnssReceiver::CheckAntenna(const libra::Vector<3> pos_true_eci_, libra::Quaternion quaternion_i2b) { - if (antenna_model_ == SIMPLE) + if (antenna_model_ == AntennaModel::kSimple) CheckAntennaSimple(pos_true_eci_, quaternion_i2b); - else if (antenna_model_ == CONE) + else if (antenna_model_ == AntennaModel::kCone) CheckAntennaCone(pos_true_eci_, quaternion_i2b); } diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index 8018fb2a5..b8c5847c4 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -20,9 +20,9 @@ * @enum AntennaModel * @brief Antenna pattern model to emulate GNSS antenna */ -enum AntennaModel { - SIMPLE, //!< Simple model which can get navigation data when the antenna points anti-earth direction - CONE, //!< Cone antenna pattern +enum class AntennaModel { + kSimple, //!< Simple model which can get navigation data when the antenna points anti-earth direction + kCone, //!< Cone antenna pattern }; /** diff --git a/src/components/real/aocs/initialize_gnss_receiver.cpp b/src/components/real/aocs/initialize_gnss_receiver.cpp index 78f7fadae..c06bf0bfc 100644 --- a/src/components/real/aocs/initialize_gnss_receiver.cpp +++ b/src/components/real/aocs/initialize_gnss_receiver.cpp @@ -20,7 +20,7 @@ typedef struct _gnssrecever_param { } GnssReceiverParam; GnssReceiverParam ReadGnssReceiverIni(const std::string file_name, const GnssSatellites* gnss_satellites, const int component_id) { - GnssReceiverParam gnssreceiver_param; + GnssReceiverParam gnss_receiver_param; IniAccess gnssr_conf(file_name); const char* sensor_name = "GNSS_RECEIVER_"; @@ -29,24 +29,24 @@ GnssReceiverParam ReadGnssReceiverIni(const std::string file_name, const GnssSat int prescaler = gnssr_conf.ReadInt(GSection, "prescaler"); if (prescaler <= 1) prescaler = 1; - gnssreceiver_param.prescaler = prescaler; + gnss_receiver_param.prescaler = prescaler; - gnssreceiver_param.antenna_model = static_cast(gnssr_conf.ReadInt(GSection, "antenna_model")); - if (!gnss_satellites->IsCalcEnabled() && gnssreceiver_param.antenna_model == CONE) { + gnss_receiver_param.antenna_model = static_cast(gnssr_conf.ReadInt(GSection, "antenna_model")); + if (!gnss_satellites->IsCalcEnabled() && gnss_receiver_param.antenna_model == AntennaModel::kCone) { std::cout << "Calculation of GNSS SATELLITES is DISABLED, so the antenna " "model of GNSS Receiver is automatically set to SIMPLE model." << std::endl; - gnssreceiver_param.antenna_model = SIMPLE; + gnss_receiver_param.antenna_model = AntennaModel::kSimple; } - gnssr_conf.ReadVector(GSection, "antenna_position_b_m", gnssreceiver_param.antenna_pos_b); - gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnssreceiver_param.quaternion_b2c); - gnssreceiver_param.half_width_rad = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); - gnssreceiver_param.gnss_id = gnssr_conf.ReadString(GSection, "gnss_id"); - gnssreceiver_param.max_channel = gnssr_conf.ReadInt(GSection, "maximum_channel"); - gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnssreceiver_param.noise_standard_deviation_m); + gnssr_conf.ReadVector(GSection, "antenna_position_b_m", gnss_receiver_param.antenna_pos_b); + gnssr_conf.ReadQuaternion(GSection, "quaternion_b2c", gnss_receiver_param.quaternion_b2c); + gnss_receiver_param.half_width_rad = gnssr_conf.ReadDouble(GSection, "antenna_half_width_deg"); + gnss_receiver_param.gnss_id = gnssr_conf.ReadString(GSection, "gnss_id"); + gnss_receiver_param.max_channel = gnssr_conf.ReadInt(GSection, "maximum_channel"); + gnssr_conf.ReadVector(GSection, "white_noise_standard_deviation_eci_m", gnss_receiver_param.noise_standard_deviation_m); - return gnssreceiver_param; + return gnss_receiver_param; } GnssReceiver InitGnssReceiver(ClockGenerator* clock_generator, int component_id, const std::string file_name, const Dynamics* dynamics, From f22db17781eef824910e715dd3dc2459bbad071c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:47:27 +0100 Subject: [PATCH 0938/1086] enum of antenna and controlled attitude --- src/components/real/communication/antenna.cpp | 18 ++++++------ src/components/real/communication/antenna.hpp | 6 ++-- .../real/communication/initialize_antenna.cpp | 4 +-- src/dynamics/attitude/controlled_attitude.cpp | 28 +++++++++---------- src/dynamics/attitude/controlled_attitude.hpp | 14 +++++----- 5 files changed, 35 insertions(+), 35 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index cf009f37f..c9e36df92 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -25,8 +25,8 @@ Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c rx_system_noise_temperature_K_ = rx_parameters[3]; // Antenna gain - tx_parameters_.antenna_gain_model = AntennaGainModel::ISOTROPIC; - rx_parameters_.antenna_gain_model = AntennaGainModel::ISOTROPIC; + tx_parameters_.antenna_gain_model = AntennaGainModel::kIsotropic; + rx_parameters_.antenna_gain_model = AntennaGainModel::kIsotropic; // Calculate the EIRP or GT for the maximum gain if (is_transmitter_) { @@ -71,10 +71,10 @@ Antenna::~Antenna() {} double Antenna::CalcAntennaGain(const AntennaParameters antenna_parameters, const double theta_rad, const double phi_rad) const { double gain_dBi = 0.0; switch (antenna_parameters.antenna_gain_model) { - case AntennaGainModel::ISOTROPIC: + case AntennaGainModel::kIsotropic: gain_dBi = antenna_parameters.gain_dBi_; break; - case AntennaGainModel::RADIATION_PATTERN_CSV: + case AntennaGainModel::kRadiationPatternCsv: gain_dBi = antenna_parameters.radiation_pattern.GetGain_dBi(theta_rad, phi_rad); break; default: @@ -91,11 +91,11 @@ double Antenna::CalcRxGt_dB_K(const double theta_rad, const double phi_rad) cons } AntennaGainModel SetAntennaGainModel(const std::string gain_model_name) { - if (gain_model_name == "ISOTROPIC") { - return AntennaGainModel::ISOTROPIC; - } else if (gain_model_name == "RADIATION_PATTERN_CSV") { - return AntennaGainModel::RADIATION_PATTERN_CSV; + if (gain_model_name == "kIsotropic") { + return AntennaGainModel::kIsotropic; + } else if (gain_model_name == "kRadiationPatternCsv") { + return AntennaGainModel::kRadiationPatternCsv; } else { - return AntennaGainModel::ISOTROPIC; + return AntennaGainModel::kIsotropic; } } diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 8620e8fc1..816790979 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -19,8 +19,8 @@ using libra::Vector; * @brief Antenna gain model definition */ enum class AntennaGainModel { - ISOTROPIC, //!< Ideal isotropic antenna - RADIATION_PATTERN_CSV, //!< Radiation pattern obtained by CSV file + kIsotropic, //!< Ideal isotropic antenna + kRadiationPatternCsv, //!< Radiation pattern obtained by CSV file }; /* @@ -28,7 +28,7 @@ enum class AntennaGainModel { * @brief Antenna parameters */ struct AntennaParameters { - double gain_dBi_; /*!< Gain used in ISOTROPIC mode [dBi] + double gain_dBi_; /*!< Gain used in kIsotropic mode [dBi] Generally, it is zero but users can set any value for ideal analysis */ double loss_feeder_dB_; //!< Feeder loss [dB] double loss_pointing_dB_; //!< Pointing loss [dB] diff --git a/src/components/real/communication/initialize_antenna.cpp b/src/components/real/communication/initialize_antenna.cpp index 2c9a9eaca..e1ff30d89 100644 --- a/src/components/real/communication/initialize_antenna.cpp +++ b/src/components/real/communication/initialize_antenna.cpp @@ -49,7 +49,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { tx_parameters.gain_dBi_ = 0.0; tx_parameters.loss_feeder_dB_ = 0.0; tx_parameters.loss_pointing_dB_ = 0.0; - tx_parameters.antenna_gain_model = AntennaGainModel::ISOTROPIC; + tx_parameters.antenna_gain_model = AntennaGainModel::kIsotropic; } AntennaParameters rx_parameters; @@ -69,7 +69,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { rx_parameters.gain_dBi_ = 0.0; rx_parameters.loss_feeder_dB_ = 0.0; rx_parameters.loss_pointing_dB_ = 0.0; - rx_parameters.antenna_gain_model = AntennaGainModel::ISOTROPIC; + rx_parameters.antenna_gain_model = AntennaGainModel::kIsotropic; } Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency_MHz, tx_output_power_W, tx_parameters, diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 23b061578..cb59a4b03 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -30,9 +30,9 @@ ControlledAttitude::~ControlledAttitude() {} // Main function void ControlledAttitude::Initialize(void) { - if (main_mode_ >= NO_CTRL) is_calc_enabled_ = false; - if (sub_mode_ >= NO_CTRL) is_calc_enabled_ = false; - if (main_mode_ == INERTIAL_STABILIZE) { + if (main_mode_ >= AttitudeControlMode::kNoControl) is_calc_enabled_ = false; + if (sub_mode_ >= AttitudeControlMode::kNoControl) is_calc_enabled_ = false; + if (main_mode_ == AttitudeControlMode::kInertialStabilize) { } else // Pointing control { // sub mode check @@ -59,7 +59,7 @@ void ControlledAttitude::Propagate(const double end_time_s) { libra::Vector<3> main_direction_i, sub_direction_i; if (!is_calc_enabled_) return; - if (main_mode_ == INERTIAL_STABILIZE) { + if (main_mode_ == AttitudeControlMode::kInertialStabilize) { // quaternion_i2b_ = quaternion_i2t_; return; } @@ -77,13 +77,13 @@ void ControlledAttitude::Propagate(const double end_time_s) { libra::Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode mode) { libra::Vector<3> direction; - if (mode == SUN_POINTING) { + if (mode == AttitudeControlMode::kSunPointing) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); - } else if (mode == EARTH_CENTER_POINTING) { + } else if (mode == AttitudeControlMode::kEarthCenterPointing) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("EARTH"); - } else if (mode == VELOCITY_DIRECTION_POINTING) { + } else if (mode == AttitudeControlMode::kVelocityDirectionPointing) { direction = orbit_->GetVelocity_i_m_s(); - } else if (mode == ORBIT_NORMAL_POINTING) { + } else if (mode == AttitudeControlMode::kOrbitNormalPointing) { direction = OuterProduct(orbit_->GetPosition_i_m(), orbit_->GetVelocity_i_m_s()); } Normalize(direction); @@ -123,17 +123,17 @@ libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_dire AttitudeControlMode ConvertStringToCtrlMode(const std::string mode) { if (mode == "INERTIAL_STABILIZE") { - return INERTIAL_STABILIZE; + return AttitudeControlMode::kInertialStabilize; } else if (mode == "SUN_POINTING") { - return SUN_POINTING; + return AttitudeControlMode::kSunPointing; } else if (mode == "EARTH_CENTER_POINTING") { - return EARTH_CENTER_POINTING; + return AttitudeControlMode::kEarthCenterPointing; } else if (mode == "VELOCITY_DIRECTION_POINTING") { - return VELOCITY_DIRECTION_POINTING; + return AttitudeControlMode::kVelocityDirectionPointing; } else if (mode == "ORBIT_NORMAL_POINTING") { - return ORBIT_NORMAL_POINTING; + return AttitudeControlMode::kOrbitNormalPointing; } else { - return NO_CTRL; + return AttitudeControlMode::kNoControl; } } diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 8ca018af1..8eba9f3b8 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -17,13 +17,13 @@ * @enum AttitudeControlMode * @brief Attitude control mode */ -enum AttitudeControlMode { - INERTIAL_STABILIZE, //!< Inertial stabilize - SUN_POINTING, //!< Sun pointing - EARTH_CENTER_POINTING, //!< Earth center pointing - VELOCITY_DIRECTION_POINTING, //!< Spacecraft velocity direction pointing - ORBIT_NORMAL_POINTING, //!< Orbit normal direction pointing - NO_CTRL, // No Control +enum class AttitudeControlMode { + kInertialStabilize, //!< Inertial stabilize + kSunPointing, //!< Sun pointing + kEarthCenterPointing, //!< Earth center pointing + kVelocityDirectionPointing, //!< Spacecraft velocity direction pointing + kOrbitNormalPointing, //!< Orbit normal direction pointing + kNoControl, // No Control }; /** From 04d6ef9f047a4ac4376b0612d170c42e2dcef1f5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 22:52:26 +0100 Subject: [PATCH 0939/1086] enum of relative orbit and celestial rotation --- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/orbit/relative_orbit.hpp | 2 +- src/environment/global/celestial_rotation.cpp | 18 +++++++++--------- src/environment/global/celestial_rotation.hpp | 8 ++++---- .../global/initialize_global_environment.cpp | 8 ++++---- 5 files changed, 20 insertions(+), 20 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index a39c82f10..e5a4e8981 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -53,7 +53,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l initial_state_[4] = relative_velocity_lvlh_m_s[1]; initial_state_[5] = relative_velocity_lvlh_m_s[2]; - if (update_method_ == RK4) { + if (update_method_ == kRk4) { Setup(initial_time_s, initial_state_); CalculateSystemMatrix(relative_dynamics_model_type_, &(relative_information_->GetReferenceSatDynamics(reference_spacecraft_id_)->GetOrbit()), gravity_constant_m3_s2); @@ -101,7 +101,7 @@ void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { spacecraft_acceleration_i_m_s2_ *= 0.0; // Disturbance acceleration are not considered in relative orbit propagation - if (update_method_ == RK4) { + if (update_method_ == kRk4) { PropagateRk4(end_time_s); } else // update_method_ == STM { diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index 568064a27..bb7562622 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -23,7 +23,7 @@ class RelativeOrbit : public Orbit, public libra::OrdinaryDifferentialEquation<6 * @enum RelativeOrbitUpdateMethod * @brief Relative orbit update method */ - typedef enum { RK4 = 0, STM = 1 } RelativeOrbitUpdateMethod; + typedef enum { kRk4 = 0, kStm = 1 } RelativeOrbitUpdateMethod; /** * @fn RelativeOrbit diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index d2bf28445..d92b7b931 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -19,7 +19,7 @@ // Default constructor CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "Anonymous"; - rotation_mode_ = Idle; + rotation_mode_ = RotationMode::kIdle; Unitalize(dcm_j2000_to_xcxf_); dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; if (center_body_name == "EARTH") { @@ -31,11 +31,11 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "EARTH"; if (center_body_name == planet_name_) { - if (rotation_mode == Simple) { - rotation_mode_ = Simple; + if (rotation_mode == RotationMode::kSimple) { + rotation_mode_ = RotationMode::kSimple; // For Simple mode, we don't need initialization of the coefficients - } else if (rotation_mode == Full) { - rotation_mode_ = Full; + } else if (rotation_mode == RotationMode::kFull) { + rotation_mode_ = RotationMode::kFull; // For Full mode, initialize the coefficients // The hard coded values are consistent with the reference document. The unit deg and rad are mixed. @@ -114,12 +114,12 @@ void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation c_z_rad_[2] = 0.018203 * libra::arcsec_to_rad; // [rad/century^3] } else { // If the rotation mode is neither Simple nor Full, disable the rotation calculation and make the DCM a unit matrix - rotation_mode_ = Idle; + rotation_mode_ = RotationMode::kIdle; Unitalize(dcm_j2000_to_xcxf_); } } else { // If the center object is not the Earth, disable the Earth's rotation calculation and make the DCM a unit matrix - rotation_mode_ = Idle; + rotation_mode_ = RotationMode::kIdle; Unitalize(dcm_j2000_to_xcxf_); } } @@ -127,7 +127,7 @@ void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation void CelestialRotation::Update(const double JulianDate) { double gmst_rad = gstime(JulianDate); // It is a bit different with 長沢(Nagasawa)'s algorithm. TODO: Check the correctness - if (rotation_mode_ == Full) { + if (rotation_mode_ == RotationMode::kFull) { // Compute Julian date for terestrial time double jdTT_day = JulianDate + kDtUt1Utc_ * kSec2Day_; // TODO: Check the correctness. Problem is thtat S2E doesn't have Gregorian calendar. @@ -158,7 +158,7 @@ void CelestialRotation::Update(const double JulianDate) { // Total orientation dcm_j2000_to_xcxf_ = W * R * N * P; - } else if (rotation_mode_ == Simple) { + } else if (rotation_mode_ == RotationMode::kSimple) { // In this case, only Axial Rotation is executed, with its argument replaced from G'A'ST to G'M'ST dcm_j2000_to_xcxf_ = AxialRotation(gmst_rad); } else { diff --git a/src/environment/global/celestial_rotation.hpp b/src/environment/global/celestial_rotation.hpp index d5bc76b95..3e978ea3c 100644 --- a/src/environment/global/celestial_rotation.hpp +++ b/src/environment/global/celestial_rotation.hpp @@ -17,10 +17,10 @@ * @enum RotationMode * @brief Definition of calculation mode of celestial rotation */ -enum RotationMode { - Idle, //!< No Rotation calculation - Simple, //!< Z axis rotation only - Full, //!< Rotation including precession and nutation +enum class RotationMode { + kIdle, //!< No Rotation calculation + kSimple, //!< Z axis rotation only + kFull, //!< Rotation including precession and nutation }; /** diff --git a/src/environment/global/initialize_global_environment.cpp b/src/environment/global/initialize_global_environment.cpp index 542db7350..15f3c75d4 100644 --- a/src/environment/global/initialize_global_environment.cpp +++ b/src/environment/global/initialize_global_environment.cpp @@ -100,14 +100,14 @@ CelestialInformation* InitCelestialInformation(std::string file_name) { RotationMode rotation_mode; std::string rotation_mode_temp = ini_file.ReadString(section, "rotation_mode"); if (rotation_mode_temp == "Idle") { - rotation_mode = Idle; + rotation_mode = RotationMode::kIdle; } else if (rotation_mode_temp == "Simple") { - rotation_mode = Simple; + rotation_mode = RotationMode::kSimple; } else if (rotation_mode_temp == "Full") { - rotation_mode = Full; + rotation_mode = RotationMode::kFull; } else // if rotation_mode is neither Idle, Simple, nor Full, set rotation_mode to Idle { - rotation_mode = Idle; + rotation_mode = RotationMode::kIdle; } CelestialInformation* celestial_info; From 6724b935ce4f3d808763f664194d39e8f865f61b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:03:30 +0100 Subject: [PATCH 0940/1086] Add TODO comment --- src/environment/global/gnss_satellites.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 9397840f3..2264c80b1 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -630,7 +630,7 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in double unix_time = (double)mktime(time_tm); const double interval = 6 * 60 * 60; if (start_unix_time < 0) { - start_unix_time = unix_time + (ur_flag - UR_OBSERVE1) * interval; + start_unix_time = unix_time + (ur_flag - UR_OBSERVE1) * interval; // Fix here to use enum class end_unix_time = start_unix_time + interval; } From e70d76bb5b04c1bde6d5fd3106f37b7ebcf64179 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:06:17 +0100 Subject: [PATCH 0941/1086] Fix enum of relative orbit model --- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/library/orbit/relative_orbit_models.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index e5a4e8981..39cae4704 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -70,7 +70,7 @@ void RelativeOrbit::InitializeState(libra::Vector<3> relative_position_lvlh_m, l void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2) { switch (relative_dynamics_model_type) { - case RelativeOrbitModel::Hill: { + case RelativeOrbitModel::kHill: { double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); system_matrix_ = CalcHillSystemMatrix(reference_sat_orbit_radius, gravity_constant_m3_s2); } @@ -83,7 +83,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2, double elapsed_sec) { switch (stm_model_type) { - case StmModel::HCW: { + case StmModel::kHcw: { double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); stm_ = CalcHcwStm(reference_sat_orbit_radius, gravity_constant_m3_s2, elapsed_sec); } diff --git a/src/library/orbit/relative_orbit_models.hpp b/src/library/orbit/relative_orbit_models.hpp index c974ac45c..a77fb5d45 100644 --- a/src/library/orbit/relative_orbit_models.hpp +++ b/src/library/orbit/relative_orbit_models.hpp @@ -13,13 +13,13 @@ * @enum RelativeOrbitModel * @brief Relative orbit model */ -enum class RelativeOrbitModel { Hill = 0 }; +enum class RelativeOrbitModel { kHill = 0 }; /** * @enum StmModel * @brief State Transition Matrix for the relative orbit */ -enum class StmModel { HCW = 0 }; +enum class StmModel { kHcw = 0 }; // Dynamics Models /** From e0bc2036217d1d99ba7df3269070d32629ca3305 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:13:10 +0100 Subject: [PATCH 0942/1086] Fix enum of monte carlo simulation --- .../initialize_monte_carlo_parameters.cpp | 24 +++++++------- .../initialize_monte_carlo_parameters.hpp | 20 ++++++------ .../initialize_monte_carlo_simulation.cpp | 32 +++++++++---------- 3 files changed, 38 insertions(+), 38 deletions(-) diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index c4a26c8d0..43ee0ccb9 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -25,7 +25,7 @@ InitializedMonteCarloParameters::InitializedMonteCarloParameters() { } // No randomization when SetRandomConfiguration is not called(No setting in MCSim.ini) - randomization_type_ = NoRandomization; + randomization_type_ = kNoRandomization; } void InitializedMonteCarloParameters::SetSeed(unsigned long seed, bool is_deterministic) { @@ -37,7 +37,7 @@ void InitializedMonteCarloParameters::SetSeed(unsigned long seed, bool is_determ } void InitializedMonteCarloParameters::GetRandomizedScalar(double& destination) const { - if (randomization_type_ == NoRandomization) { + if (randomization_type_ == kNoRandomization) { ; } else if (1 > randomized_value_.size()) { throw "Too few randomization configuration parameters."; @@ -47,7 +47,7 @@ void InitializedMonteCarloParameters::GetRandomizedScalar(double& destination) c } void InitializedMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& destination) const { - if (randomization_type_ == NoRandomization) { + if (randomization_type_ == kNoRandomization) { ; } else if (4 > randomized_value_.size()) { throw "Too few randomization configuration parameters."; @@ -62,31 +62,31 @@ void InitializedMonteCarloParameters::GetRandomizedQuaternion(libra::Quaternion& void InitializedMonteCarloParameters::Randomize() { switch (randomization_type_) { - case NoRandomization: + case kNoRandomization: GenerateNoRandomization(); break; - case CartesianUniform: + case kCartesianUniform: GenerateCartesianUniform(); break; - case CartesianNormal: + case kCartesianNormal: GenerateCartesianNormal(); break; - case CircularNormalUniform: + case kCircularNormalUniform: GenerateCircularNormalUniform(); break; - case CircularNormalNormal: + case kCircularNormalNormal: GenerateCircularNormalNormal(); break; - case SphericalNormalUniformUniform: + case kSphericalNormalUniformUniform: GenerateSphericalNormalUniformUniform(); break; - case SphericalNormalNormal: + case kSphericalNormalNormal: GenerateSphericalNormalNormal(); break; - case QuaternionUniform: + case kQuaternionUniform: GenerateQuaternionUniform(); break; - case QuaternionNormal: + case kQuaternionNormal: GenerateQuaternionNormal(); break; default: diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp index 9b4fc13cd..193a5f6a2 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.hpp @@ -24,15 +24,15 @@ class InitializedMonteCarloParameters { * @brief Randomization type */ enum RandomizationType { - NoRandomization, //!< Output default value - CartesianUniform, //!< Random variables following a uniform distribution in Cartesian frame - CartesianNormal, //!< Random variables following a normal distribution in Cartesian frame - CircularNormalUniform, //!< r follows normal distribution, and θ follows uniform distribution in Circular frame - CircularNormalNormal, //!< r and θ follow normal distribution in Circular frame - SphericalNormalUniformUniform, //!< r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame - SphericalNormalNormal, //!< r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] - QuaternionUniform, //!< Perfectly Randomized libra::Quaternion - QuaternionNormal, //!< Angle from the default quaternion θ follows normal distribution + kNoRandomization, //!< Output default value + kCartesianUniform, //!< Random variables following a uniform distribution in Cartesian frame + kCartesianNormal, //!< Random variables following a normal distribution in Cartesian frame + kCircularNormalUniform, //!< r follows normal distribution, and θ follows uniform distribution in Circular frame + kCircularNormalNormal, //!< r and θ follow normal distribution in Circular frame + kSphericalNormalUniformUniform, //!< r follows normal distribution, and θ and φ follow uniform distribution in Spherical frame + kSphericalNormalNormal, //!< r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] + kQuaternionUniform, //!< Perfectly Randomized libra::Quaternion + kQuaternionNormal, //!< Angle from the default quaternion θ follows normal distribution }; /** @@ -221,7 +221,7 @@ void InitializedMonteCarloParameters::SetRandomConfiguration(const libra::Vector template void InitializedMonteCarloParameters::GetRandomizedVector(libra::Vector& destination) const { - if (randomization_type_ == NoRandomization) { + if (randomization_type_ == kNoRandomization) { ; } else if (NumElement > randomized_value_.size()) { throw "Too few randomization configuration parameters."; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp index 89618aa86..dbe10646b 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_simulation.cpp @@ -28,20 +28,20 @@ MonteCarloSimulationExecutor* InitMonteCarloSimulation(std::string file_name) { std::vector so_dot_ip_str_vec = ini_file.ReadStrVector(section, "parameter"); std::vector so_str_vec, ip_str_vec; - enum Phase { FoundNothingYet, FoundSimulationObjectStr, FoundInitParameterStr }; + enum Phase { kFoundNothingYet, kFoundSimulationObjectStr, kFoundInitParameterStr }; for (auto so_dot_ip_str : so_dot_ip_str_vec) { // Divide the string to SimulationObject and InitializedMonteCarloParameters - Phase phase = FoundNothingYet; + Phase phase = kFoundNothingYet; std::stringstream ss(so_dot_ip_str); std::string item, so_str, ip_str; while (getline(ss, item, MonteCarloSimulationExecutor::separator_)) { if (!item.empty()) { - if (phase == FoundNothingYet) { - phase = FoundSimulationObjectStr; + if (phase == kFoundNothingYet) { + phase = kFoundSimulationObjectStr; so_str = item; so_str_vec.push_back(so_str); - } else if (phase == FoundSimulationObjectStr) { - phase = FoundInitParameterStr; + } else if (phase == kFoundSimulationObjectStr) { + phase = kFoundInitParameterStr; ip_str = item; ip_str_vec.push_back(ip_str); break; @@ -57,25 +57,25 @@ MonteCarloSimulationExecutor* InitMonteCarloSimulation(std::string file_name) { ini_file.ReadChar(section, key_name.c_str(), buf_size, rnd_type_str); if (!strcmp(rnd_type_str, "NoRandomization")) - random_type = InitializedMonteCarloParameters::NoRandomization; + random_type = InitializedMonteCarloParameters::kNoRandomization; else if (!strcmp(rnd_type_str, "CartesianUniform")) - random_type = InitializedMonteCarloParameters::CartesianUniform; + random_type = InitializedMonteCarloParameters::kCartesianUniform; else if (!strcmp(rnd_type_str, "CartesianNormal")) - random_type = InitializedMonteCarloParameters::CartesianNormal; + random_type = InitializedMonteCarloParameters::kCartesianNormal; else if (!strcmp(rnd_type_str, "CircularNormalUniform")) - random_type = InitializedMonteCarloParameters::CircularNormalUniform; + random_type = InitializedMonteCarloParameters::kCircularNormalUniform; else if (!strcmp(rnd_type_str, "CircularNormalNormal")) - random_type = InitializedMonteCarloParameters::CircularNormalNormal; + random_type = InitializedMonteCarloParameters::kCircularNormalNormal; else if (!strcmp(rnd_type_str, "SphericalNormalUniformUniform")) - random_type = InitializedMonteCarloParameters::SphericalNormalUniformUniform; + random_type = InitializedMonteCarloParameters::kSphericalNormalUniformUniform; else if (!strcmp(rnd_type_str, "SphericalNormalNormal")) - random_type = InitializedMonteCarloParameters::SphericalNormalNormal; + random_type = InitializedMonteCarloParameters::kSphericalNormalNormal; else if (!strcmp(rnd_type_str, "QuaternionUniform")) - random_type = InitializedMonteCarloParameters::QuaternionUniform; + random_type = InitializedMonteCarloParameters::kQuaternionUniform; else if (!strcmp(rnd_type_str, "QuaternionNormal")) - random_type = InitializedMonteCarloParameters::QuaternionNormal; + random_type = InitializedMonteCarloParameters::kQuaternionNormal; else - random_type = InitializedMonteCarloParameters::NoRandomization; + random_type = InitializedMonteCarloParameters::kNoRandomization; // Read mean_or_min vector key_name = so_dot_ip_str + MonteCarloSimulationExecutor::separator_ + "mean_or_min"; From 00271d5f142dc81bfbb30eef68554ecbc6e00c74 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:15:16 +0100 Subject: [PATCH 0943/1086] Fix enum of port setting --- .../sample_port_configuration.hpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp index fb1ece1e6..24ff21316 100644 --- a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp +++ b/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp @@ -9,22 +9,22 @@ /** * @enum PowerPortConfig * @brief ID list of electrical power switch ports - * @details Register sequential same with port_id. Use NONE_1, NONE_2 if the number is skipped. + * @details Register sequential same with port_id. Use kNone1, kNone2 if the number is skipped. */ -enum PowerPortConfig { - OBC_BUS, - GYRO_5V, - COMPONENT_MAX //!< Maximum port number. Do not remove. Place on the bottom. +enum class PowerPortConfig { + kObcBus, + kGyro5v, + kComponentMax //!< Maximum port number. Do not remove. Place on the bottom. }; /** * @enum UARTPortConfig * @brief ID list of serial communication ports with UART - * @details Register sequential same with port_id. Use NONE_1, NONE_2 if the number is skipped. + * @details Register sequential same with port_id. Use kNone1, kNone2 if the number is skipped. */ -enum UARTPortConfig { - GYRO = 0, - UART_COMPONENT_MAX //!< Maximum port number. Do not remove. Place on the bottom. +enum class UARTPortConfig { + kGyro = 0, + kUartComponentMax //!< Maximum port number. Do not remove. Place on the bottom. }; #endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ From e09d4e20f22e4b5acef09933f5fd2bcbe48cc44a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:24:47 +0100 Subject: [PATCH 0944/1086] Fix enum of gnss satellites --- src/environment/global/gnss_satellites.cpp | 30 ++++++------- src/environment/global/gnss_satellites.hpp | 43 ++++++++++--------- .../global/initialize_gnss_satellites.cpp | 20 ++++----- 3 files changed, 47 insertions(+), 46 deletions(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 2264c80b1..109af182c 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -224,7 +224,7 @@ bool GnssSat_coordinate::GetWhetherValid(int gnss_satellite_id) const { return validate_.at(gnss_satellite_id); } -pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, UR_KINDS ur_flag) { +pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, UltraRapidMode ur_flag) { UNUSED(interpolation_method); interpolation_number_ = interpolation_number; @@ -274,11 +274,11 @@ pair GnssSat_position::Init(vector>& file, int in while (file.at(page).at(line).front() != '*') ++line; int start_line, end_line; - if (ur_flag == UR_NOT_UR) { + if (ur_flag == kNotUse) { start_line = line; end_line = line + (num_of_sat + 1) * num_of_time_stamps; } else { - int offset = (int)ur_flag - (int)UR_OBSERVE1; + int offset = (int)ur_flag - (int)kObserve1; start_line = line + (num_of_sat + 1) * num_of_time_stamps / 8 * offset; end_line = line + (num_of_sat + 1) * num_of_time_stamps / 8 * (offset + 1); } @@ -505,7 +505,7 @@ libra::Vector<3> GnssSat_position::GetSatEci(int gnss_satellite_id) const { return gnss_sat_eci_.at(gnss_satellite_id); } -void GnssSat_clock::Init(vector>& file, string file_extension, int interpolation_number, UR_KINDS ur_flag, +void GnssSat_clock::Init(vector>& file, string file_extension, int interpolation_number, UltraRapidMode ur_flag, pair unix_time_period) { interpolation_number_ = interpolation_number; gnss_sat_clock_table_.resize(all_sat_num_); // first vector size is the sat num @@ -548,11 +548,11 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in while (file.at(page).at(line).front() != '*') ++line; int start_line, end_line; - if (ur_flag == UR_NOT_UR) { + if (ur_flag == kNotUse) { start_line = line; end_line = line + (num_of_sat + 1) * num_of_time_stamps; } else { - int offset = (int)ur_flag - (int)UR_OBSERVE1; + int offset = (int)ur_flag - (int)kObserve1; start_line = line + (num_of_sat + 1) * num_of_time_stamps / 8 * offset; end_line = line + (num_of_sat + 1) * num_of_time_stamps / 8 * (offset + 1); } @@ -594,7 +594,7 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in } } } else { // .clk30s - if (UR_PREDICT1 <= ur_flag && ur_flag <= UR_PREDICT4) { + if (kPredict1 <= ur_flag && ur_flag <= kPredict4) { cout << "clock settings has something wrong" << endl; exit(1); } @@ -602,7 +602,7 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in for (int page = 0; page < (int)file.size(); ++page) { double start_unix_time, end_unix_time; - if (ur_flag == UR_NOT_UR) { + if (ur_flag == kNotUse) { start_unix_time = unix_time_period.first; end_unix_time = unix_time_period.second + 30; } else { @@ -630,7 +630,7 @@ void GnssSat_clock::Init(vector>& file, string file_extension, in double unix_time = (double)mktime(time_tm); const double interval = 6 * 60 * 60; if (start_unix_time < 0) { - start_unix_time = unix_time + (ur_flag - UR_OBSERVE1) * interval; // Fix here to use enum class + start_unix_time = unix_time + (ur_flag - kObserve1) * interval; // Fix here to use enum class end_unix_time = start_unix_time + interval; } @@ -792,8 +792,8 @@ double GnssSat_clock::GetSatClock(int gnss_satellite_id) const { GnssSat_Info::GnssSat_Info() {} void GnssSat_Info::Init(vector>& position_file, int position_interpolation_method, int position_interpolation_number, - UR_KINDS position_ur_flag, vector>& clock_file, string clock_file_extension, int clock_interpolation_number, - UR_KINDS clock_ur_flag) { + UltraRapidMode position_ur_flag, vector>& clock_file, string clock_file_extension, int clock_interpolation_number, + UltraRapidMode clock_ur_flag) { auto unix_time_period = position_.Init(position_file, position_interpolation_method, position_interpolation_number, position_ur_flag); clock_.Init(clock_file, clock_file_extension, clock_interpolation_number, clock_ur_flag, unix_time_period); } @@ -845,16 +845,16 @@ GnssSatellites::GnssSatellites(bool is_calc_enabled) bool GnssSatellites::IsCalcEnabled() const { return is_calc_enabled_; } void GnssSatellites::Init(vector>& true_position_file, int true_position_interpolation_method, int true_position_interpolation_number, - UR_KINDS true_position_ur_flag, + UltraRapidMode true_position_ur_flag, vector>& true_clock_file, string true_clock_file_extension, int true_clock_interpolation_number, - UR_KINDS true_clock_ur_flag, + UltraRapidMode true_clock_ur_flag, vector>& estimate_position_file, int estimate_position_interpolation_method, - int estimate_position_interpolation_number, UR_KINDS estimate_position_ur_flag, + int estimate_position_interpolation_number, UltraRapidMode estimate_position_ur_flag, vector>& estimate_clock_file, string estimate_clock_file_extension, int estimate_clock_interpolation_number, - UR_KINDS estimate_clock_ur_flag) { + UltraRapidMode estimate_clock_ur_flag) { true_info_.Init(true_position_file, true_position_interpolation_method, true_position_interpolation_number, true_position_ur_flag, true_clock_file, true_clock_file_extension, true_clock_interpolation_number, true_clock_ur_flag); diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 8bf65f268..1bb035462 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -30,25 +30,26 @@ extern const double nan99; //!< Not at Number TODO: Should be moved to another // #define GNSS_SATELLITES_DEBUG_OUTPUT //!< For debug output, uncomment this /** - * @enum UR_KINDS + * @enum UltraRapidMode * @brief Ultra Rapid mode * @details When Using Ultra Rapid ephemerides, decide to use which 6 hours in each observe and predict 24 hours + * @note TODO: change to class */ -typedef enum { - UR_NOT_UR, //!< Don't use ultra rapid +enum UltraRapidMode{ + kNotUse, //!< Don't use ultra rapid - UR_OBSERVE1, //!< the most oldest observe 6 hours (most precise) - UR_OBSERVE2, //!< the second oldest observe 6 hours (6 ~ 12) - UR_OBSERVE3, - UR_OBSERVE4, + kObserve1, //!< the most oldest observe 6 hours (most precise) + kObserve2, //!< the second oldest observe 6 hours (6 ~ 12) + kObserve3, + kObserve4, - UR_PREDICT1, //!< the most oldest preserve 6 hours (most precise) - UR_PREDICT2, - UR_PREDICT3, - UR_PREDICT4, + kPredict1, //!< the most oldest preserve 6 hours (most precise) + kPredict2, + kPredict3, + kPredict4, - UR_UNKNOWN -} UR_KINDS; + kUnknown +}; /** * @class GnssSat_coordinate @@ -137,7 +138,7 @@ class GnssSat_position : public GnssSat_coordinate { * @param[in] ur_flag: Ultra Rapid flag for position calculation * @return Start unix time and end unix time */ - std::pair Init(std::vector>& file, int interpolation_method, int interpolation_number, UR_KINDS ur_flag); + std::pair Init(std::vector>& file, int interpolation_method, int interpolation_number, UltraRapidMode ur_flag); /** * @fn Setup @@ -196,7 +197,7 @@ class GnssSat_clock : public GnssSat_coordinate { * @param[in] interpolation_number: Interpolation number for clock calculation * @param[in] ur_flag: Ultra Rapid flag for clock calculation */ - void Init(std::vector>& file, std::string file_extension, int interpolation_number, UR_KINDS ur_flag, + void Init(std::vector>& file, std::string file_extension, int interpolation_number, UltraRapidMode ur_flag, std::pair unix_time_period); /** * @fn SetUp @@ -248,8 +249,8 @@ class GnssSat_Info { * @param[in] clock_ur_flag: Ultra Rapid flag for clock calculation */ void Init(std::vector>& position_file, int position_interpolation_method, int position_interpolation_number, - UR_KINDS position_ur_flag, std::vector>& clock_file, std::string clock_file_extension, - int clock_interpolation_number, UR_KINDS clock_ur_flag); + UltraRapidMode position_ur_flag, std::vector>& clock_file, std::string clock_file_extension, + int clock_interpolation_number, UltraRapidMode clock_ur_flag); /** * @fn SetUp * @brief Setup GNSS satellite position and clock information @@ -334,11 +335,11 @@ class GnssSatellites : public ILoggable { * @note Parameters are defined in GNSSSat_Info for true and estimated information */ void Init(std::vector>& true_position_file, int true_position_interpolation_method, int true_position_interpolation_number, - UR_KINDS true_position_ur_flag, std::vector>& true_clock_file, std::string true_clock_file_extension, - int true_clock_interpolation_number, UR_KINDS true_clock_ur_flag, std::vector>& estimate_position_file, - int estimate_position_interpolation_method, int estimate_position_interpolation_number, UR_KINDS estimate_position_ur_flag, + UltraRapidMode true_position_ur_flag, std::vector>& true_clock_file, std::string true_clock_file_extension, + int true_clock_interpolation_number, UltraRapidMode true_clock_ur_flag, std::vector>& estimate_position_file, + int estimate_position_interpolation_method, int estimate_position_interpolation_number, UltraRapidMode estimate_position_ur_flag, std::vector>& estimate_clock_file, std::string estimate_clock_file_extension, - int estimate_clock_interpolation_number, UR_KINDS estimate_clock_ur_flag); + int estimate_clock_interpolation_number, UltraRapidMode estimate_clock_ur_flag); /** * @fn IsCalcEnabled * @brief Return calculated enabled flag diff --git a/src/environment/global/initialize_gnss_satellites.cpp b/src/environment/global/initialize_gnss_satellites.cpp index ff88fadac..debbc3b85 100644 --- a/src/environment/global/initialize_gnss_satellites.cpp +++ b/src/environment/global/initialize_gnss_satellites.cpp @@ -65,9 +65,9 @@ void get_raw_contents(std::string directory_path, std::string file_name, std::ve } void get_sp3_file_contents(std::string directory_path, std::string file_sort, std::string first, std::string last, - std::vector>& file_contents, UR_KINDS& ur_flag) { + std::vector>& file_contents, UltraRapidMode& ur_flag) { std::string all_directory_path = directory_path + return_dirctory_path(file_sort); - ur_flag = UR_NOT_UR; + ur_flag = kNotUse; if (first.substr(0, 3) == "COD") { std::string file_header = "COD0MGXFIN_"; @@ -100,7 +100,7 @@ void get_sp3_file_contents(std::string directory_path, std::string file_sort, st ++day; } } else if (file_sort.substr(0, 3) == "IGU" || file_sort.find("Ultra") != std::string::npos) { // In case of UR - ur_flag = UR_UNKNOWN; + ur_flag = kUnknown; std::string file_header, file_footer; int gps_week = 0, day = 0; int hour = 0; @@ -265,14 +265,14 @@ GnssSatellites* InitGnssSatellites(std::string file_name) { std::string directory_path = ini_file.ReadString(section, "directory_path"); std::vector> true_position_file; - UR_KINDS true_position_ur_flag = UR_NOT_UR; + UltraRapidMode true_position_ur_flag = kNotUse; get_sp3_file_contents(directory_path, ini_file.ReadString(section, "true_position_file_sort"), ini_file.ReadString(section, "true_position_first"), ini_file.ReadString(section, "true_position_last"), true_position_file, true_position_ur_flag); int true_position_interpolation_method = ini_file.ReadInt(section, "true_position_interpolation_method"); int true_position_interpolation_number = ini_file.ReadInt(section, "true_position_interpolation_number"); std::vector> true_clock_file; - UR_KINDS true_clock_ur_flag = UR_NOT_UR; + UltraRapidMode true_clock_ur_flag = kNotUse; std::string true_clock_file_extension = ini_file.ReadString(section, "true_clock_file_extension"); if (true_clock_file_extension == ".sp3") { get_sp3_file_contents(directory_path, ini_file.ReadString(section, "true_clock_file_sort"), ini_file.ReadString(section, "true_clock_first"), @@ -284,23 +284,23 @@ GnssSatellites* InitGnssSatellites(std::string file_name) { int true_clock_interpolation_number = ini_file.ReadInt(section, "true_clock_interpolation_number"); std::vector> estimate_position_file; - UR_KINDS estimate_position_ur_flag = UR_NOT_UR; + UltraRapidMode estimate_position_ur_flag = kNotUse; get_sp3_file_contents(directory_path, ini_file.ReadString(section, "estimate_position_file_sort"), ini_file.ReadString(section, "estimate_position_first"), ini_file.ReadString(section, "estimate_position_last"), estimate_position_file, estimate_position_ur_flag); int estimate_position_interpolation_method = ini_file.ReadInt(section, "estimate_position_interpolation_method"); int estimate_position_interpolation_number = ini_file.ReadInt(section, "estimate_position_interpolation_number"); - if (estimate_position_ur_flag != UR_NOT_UR) { + if (estimate_position_ur_flag != kNotUse) { std::string ur_flag = ini_file.ReadString(section, "estimate_ur_observe_or_predict"); if (ur_flag.find("observe") != std::string::npos) { - estimate_position_ur_flag = (UR_KINDS)((int)UR_OBSERVE1 + (ur_flag.back() - '1')); + estimate_position_ur_flag = (UltraRapidMode)((int)kObserve1 + (ur_flag.back() - '1')); } else { - estimate_position_ur_flag = (UR_KINDS)((int)UR_PREDICT1 + (ur_flag.back() - '1')); + estimate_position_ur_flag = (UltraRapidMode)((int)kPredict1 + (ur_flag.back() - '1')); } } std::vector> estimate_clock_file; - UR_KINDS estimate_clock_ur_flag = estimate_position_ur_flag; + UltraRapidMode estimate_clock_ur_flag = estimate_position_ur_flag; std::string estimate_clock_file_extension = ini_file.ReadString(section, "estimate_clock_file_extension"); if (estimate_clock_file_extension == ".sp3") { get_sp3_file_contents(directory_path, ini_file.ReadString(section, "estimate_clock_file_sort"), From c8d272672487fb64edd16a6c9fd0e60b61ebae0b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:34:10 +0100 Subject: [PATCH 0945/1086] Change to enum --- src/environment/global/gnss_satellites.cpp | 14 +++++++------- src/environment/global/gnss_satellites.hpp | 21 ++++++++++----------- 2 files changed, 17 insertions(+), 18 deletions(-) diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 109af182c..9ef6079b0 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -968,7 +968,7 @@ double GnssSatellites::GetPseudoRangeECEF(const int gnss_satellite_id, libra::Ve res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, GnssFrameDefinition::kEcef); res += ionospheric_delay; @@ -990,7 +990,7 @@ double GnssSatellites::GetPseudoRangeECI(const int gnss_satellite_id, libra::Vec res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, GnssFrameDefinition::kEci); res += ionospheric_delay; @@ -1013,7 +1013,7 @@ pair GnssSatellites::GetCarrierPhaseECEF(const int gnss_satellit res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECEF); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, GnssFrameDefinition::kEcef); res -= ionospheric_delay; @@ -1043,7 +1043,7 @@ pair GnssSatellites::GetCarrierPhaseECI(const int gnss_satellite res += rec_clock - true_info_.GetSatelliteClock(gnss_satellite_id); // ionospheric delay - const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, ECI); + const double ionospheric_delay = AddIonosphericDelay(gnss_satellite_id, rec_position, frequency, GnssFrameDefinition::kEci); res -= ionospheric_delay; @@ -1059,7 +1059,7 @@ pair GnssSatellites::GetCarrierPhaseECI(const int gnss_satellite // for Ionospheric delay I[m] double GnssSatellites::AddIonosphericDelay(const int gnss_satellite_id, const libra::Vector<3> rec_position, const double frequency, - const bool flag) const { + const GnssFrameDefinition flag) const { // gnss_satellite_id is wrong or not validate if (gnss_satellite_id >= GetNumOfSatellites() || !GetWhetherValid(gnss_satellite_id)) return 0.0; @@ -1072,9 +1072,9 @@ double GnssSatellites::AddIonosphericDelay(const int gnss_satellite_id, const li if (altitude >= 1000.0) return 0.0; // there is no Ionosphere above 1000km libra::Vector<3> gnss_position; - if (flag == ECEF) + if (flag == GnssFrameDefinition::kEcef) gnss_position = true_info_.GetSatellitePositionEcef(gnss_satellite_id); - else if (flag == ECI) + else if (flag == GnssFrameDefinition::kEci) gnss_position = true_info_.GetSatellitePositionEci(gnss_satellite_id); double angle_rad = CalcAngleTwoVectors_rad(rec_position, gnss_position - rec_position); diff --git a/src/environment/global/gnss_satellites.hpp b/src/environment/global/gnss_satellites.hpp index 1bb035462..f803fafdc 100644 --- a/src/environment/global/gnss_satellites.hpp +++ b/src/environment/global/gnss_satellites.hpp @@ -19,13 +19,10 @@ extern const double nan99; //!< Not at Number TODO: Should be moved to another place -// TODO: Use enum -#define ECEF 0 //!< Use ECEF frame for GNSS satellite position frame in Add_IonosphericDelay -#define ECI 1 //!< Use ECI frame for GNSS satellite position frame in Add_IonosphericDelay - -// TODO: Not used now. Remove? Use enum? -#define Lagrange 0 //!< Use Lagrange interpolation -#define Trigonometric 1 //!< Use Trigonometric interpolation +enum class GnssFrameDefinition { + kEcef = 0, //!< Use ECEF frame for GNSS satellite position frame in Add_IonosphericDelay + kEci = 1 //!< Use ECI frame for GNSS satellite position frame in Add_IonosphericDelay +}; // #define GNSS_SATELLITES_DEBUG_OUTPUT //!< For debug output, uncomment this @@ -33,9 +30,9 @@ extern const double nan99; //!< Not at Number TODO: Should be moved to another * @enum UltraRapidMode * @brief Ultra Rapid mode * @details When Using Ultra Rapid ephemerides, decide to use which 6 hours in each observe and predict 24 hours - * @note TODO: change to class + * @note TODO: change to enum class */ -enum UltraRapidMode{ +enum UltraRapidMode { kNotUse, //!< Don't use ultra rapid kObserve1, //!< the most oldest observe 6 hours (most precise) @@ -138,7 +135,8 @@ class GnssSat_position : public GnssSat_coordinate { * @param[in] ur_flag: Ultra Rapid flag for position calculation * @return Start unix time and end unix time */ - std::pair Init(std::vector>& file, int interpolation_method, int interpolation_number, UltraRapidMode ur_flag); + std::pair Init(std::vector>& file, int interpolation_method, int interpolation_number, + UltraRapidMode ur_flag); /** * @fn Setup @@ -498,7 +496,8 @@ class GnssSatellites : public ILoggable { * @param [in] flag: The frame definition of the receiver position (ECI or ECEF) * @return Ionospheric delay [m] */ - double AddIonosphericDelay(const int gnss_satellite_id, const libra::Vector<3> rec_position, const double frequency, const bool flag) const; + double AddIonosphericDelay(const int gnss_satellite_id, const libra::Vector<3> rec_position, const double frequency, + const GnssFrameDefinition flag) const; bool is_calc_enabled_ = true; //!< Flag to manage the GNSS satellite position calculation GnssSat_Info true_info_; //!< True information of GNSS satellites From 94db919c2f43fa4c1eb64b21f34d7d4d3651bb2a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 28 Feb 2023 23:49:00 +0100 Subject: [PATCH 0946/1086] Fix format --- src/components/base/i2c_controller.hpp | 8 ++++---- src/components/real/aocs/gyro_sensor.cpp | 2 +- src/components/real/communication/antenna.hpp | 2 +- src/environment/global/gnss_satellites.cpp | 7 ++++--- 4 files changed, 10 insertions(+), 9 deletions(-) diff --git a/src/components/base/i2c_controller.hpp b/src/components/base/i2c_controller.hpp index a75c9545e..62f59e480 100644 --- a/src/components/base/i2c_controller.hpp +++ b/src/components/base/i2c_controller.hpp @@ -55,10 +55,10 @@ class I2cController { std::vector rx_buffer_; //!< RX (Target to Controller) buffer private: - unsigned int hils_port_id_; //!< ID of HILS communication port - unsigned int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 - unsigned int tx_buffer_size_; //!< TX (Controller to Target) buffer size - unsigned int rx_buffer_size_; //!< RX (Target to Controller) buffer size + unsigned int hils_port_id_; //!< ID of HILS communication port + unsigned int baud_rate_; //!< Baud rate of HILS communication port ex. 9600, 115200 + unsigned int tx_buffer_size_; //!< TX (Controller to Target) buffer size + unsigned int rx_buffer_size_; //!< RX (Target to Controller) buffer size SimulationMode simulation_mode_ = SimulationMode::kError; //!< Simulation mode (SILS or HILS) HilsPortManager* hils_port_manager_; //!< HILS port manager diff --git a/src/components/real/aocs/gyro_sensor.cpp b/src/components/real/aocs/gyro_sensor.cpp index e9eec6c4e..289810b17 100644 --- a/src/components/real/aocs/gyro_sensor.cpp +++ b/src/components/real/aocs/gyro_sensor.cpp @@ -23,7 +23,7 @@ void GyroSensor::MainRoutine(const int time_count) { UNUSED(time_count); angular_velocity_c_rad_s_ = quaternion_b2c_.FrameConversion(dynamics_->GetAttitude().GetAngularVelocity_b_rad_s()); // Convert frame - angular_velocity_c_rad_s_ = Measure(angular_velocity_c_rad_s_); // Add noises + angular_velocity_c_rad_s_ = Measure(angular_velocity_c_rad_s_); // Add noises } std::string GyroSensor::GetLogHeader() const { diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 816790979..ccbfcd87e 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -19,7 +19,7 @@ using libra::Vector; * @brief Antenna gain model definition */ enum class AntennaGainModel { - kIsotropic, //!< Ideal isotropic antenna + kIsotropic, //!< Ideal isotropic antenna kRadiationPatternCsv, //!< Radiation pattern obtained by CSV file }; diff --git a/src/environment/global/gnss_satellites.cpp b/src/environment/global/gnss_satellites.cpp index 9ef6079b0..9dbea10ee 100644 --- a/src/environment/global/gnss_satellites.cpp +++ b/src/environment/global/gnss_satellites.cpp @@ -224,7 +224,8 @@ bool GnssSat_coordinate::GetWhetherValid(int gnss_satellite_id) const { return validate_.at(gnss_satellite_id); } -pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, UltraRapidMode ur_flag) { +pair GnssSat_position::Init(vector>& file, int interpolation_method, int interpolation_number, + UltraRapidMode ur_flag) { UNUSED(interpolation_method); interpolation_number_ = interpolation_number; @@ -792,8 +793,8 @@ double GnssSat_clock::GetSatClock(int gnss_satellite_id) const { GnssSat_Info::GnssSat_Info() {} void GnssSat_Info::Init(vector>& position_file, int position_interpolation_method, int position_interpolation_number, - UltraRapidMode position_ur_flag, vector>& clock_file, string clock_file_extension, int clock_interpolation_number, - UltraRapidMode clock_ur_flag) { + UltraRapidMode position_ur_flag, vector>& clock_file, string clock_file_extension, + int clock_interpolation_number, UltraRapidMode clock_ur_flag) { auto unix_time_period = position_.Init(position_file, position_interpolation_method, position_interpolation_number, position_ur_flag); clock_.Init(clock_file, clock_file_extension, clock_interpolation_number, clock_ur_flag, unix_time_period); } From 5cdc651ba8a0c83b9fadb1e0bef44b6006a9bf5b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 09:08:53 +0100 Subject: [PATCH 0947/1086] Fix build settings for TEST --- CMakeLists.txt | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index c8a61f8ea..027d8f3c8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -196,6 +196,12 @@ if(GOOGLE_TEST) include_directories(${TEST_PROJECT_NAME}) add_test(NAME s2e-test COMMAND ${TEST_PROJECT_NAME}) enable_testing() + + # Settings + set_target_properties(${TEST_PROJECT_NAME} PROPERTIES LANGUAGE CXX) + set_target_properties(${TEST_PROJECT_NAME} PROPERTIES CXX_STANDARD 17) + set_target_properties(${TEST_PROJECT_NAME} PROPERTIES CXX_EXTENSIONS FALSE) + endif() From 0c55084372cc78d2ce54b443de5044fba8b47ed4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 09:09:03 +0100 Subject: [PATCH 0948/1086] Add Quaternion test --- src/library/math/test_quaternion.cpp | 156 ++++++++++++++++++++++++++- 1 file changed, 152 insertions(+), 4 deletions(-) diff --git a/src/library/math/test_quaternion.cpp b/src/library/math/test_quaternion.cpp index 915ff8f94..74bf58e4f 100644 --- a/src/library/math/test_quaternion.cpp +++ b/src/library/math/test_quaternion.cpp @@ -5,7 +5,11 @@ #include #include "quaternion.hpp" +#include "constants.hpp" +/** + * @brief Test for constructor from four numbers + */ TEST(Quaternion, ConstructorFourNumber) { libra::Quaternion q(0.5, 0.5, 0.5, 0.5); @@ -15,6 +19,9 @@ TEST(Quaternion, ConstructorFourNumber) { EXPECT_DOUBLE_EQ(0.5, q[3]); } +/** + * @brief Test for constructor from Vector + */ TEST(Quaternion, ConstructorVector) { libra::Vector<4> v(0.5); libra::Quaternion q(v); @@ -25,16 +32,157 @@ TEST(Quaternion, ConstructorVector) { EXPECT_DOUBLE_EQ(0.5, q[3]); } -TEST(Quaternion, ConstructorAxisRot) { +/** + * @brief Test for constructor from axis and rotation angle X rotation + */ +TEST(Quaternion, ConstructorAxisAndAngleX) { libra::Vector<3> axis; axis[0] = 1.0; axis[1] = 0.0; axis[2] = 0.0; - double theta_rad = 1.5708; + double theta_rad = 90 * libra::deg_to_rad; + libra::Quaternion q(axis, theta_rad); + + EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from axis and rotation angle Y rotation + */ +TEST(Quaternion, ConstructorAxisAndAngleY) { + libra::Vector<3> axis; + axis[0] = 0.0; + axis[1] = 1.0; + axis[2] = 0.0; + double theta_rad = 45 * libra::deg_to_rad; + libra::Quaternion q(axis, theta_rad); + + EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from axis and rotation angle Z rotation + */ +TEST(Quaternion, ConstructorAxisAndAngleZ) { + libra::Vector<3> axis; + axis[0] = 0.0; + axis[1] = 0.0; + axis[2] = 1.0; + double theta_rad = -60 * libra::deg_to_rad; + libra::Quaternion q(axis, theta_rad); + + EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from axis and rotation angle All axes rotation + */ +TEST(Quaternion, ConstructorAxisAndAngleAll) { + libra::Vector<3> axis; + axis[0] = 1.0; + axis[1] = 1.0; + axis[2] = 1.0; + double theta_rad = 180 * libra::deg_to_rad; libra::Quaternion q(axis, theta_rad); - EXPECT_NEAR(1 / sqrt(2), q[0], 1e-5); + EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from two vectors: No rotation + */ +TEST(Quaternion, ConstructorTwoVectorsNoRotation) { + libra::Vector<3> before; + before[0] = 0.0; + before[1] = 0.0; + before[2] = 2.0; // To check normalization + libra::Vector<3> after; + after[0] = 0.0; + after[1] = 0.0; + after[2] = 1.0; + + libra::Quaternion q(before, after); + + EXPECT_NEAR(0.0, q[0], 1e-5); + EXPECT_NEAR(0.0, q[1], 1e-5); + EXPECT_NEAR(0.0, q[2], 1e-5); + EXPECT_NEAR(1.0, q[3], 1e-5); +} + +/** + * @brief Test for constructor from two vectors: X rotation + */ +TEST(Quaternion, ConstructorTwoVectorsX) { + libra::Vector<3> before; + before[0] = 0.0; + before[1] = 0.0; + before[2] = 1.0; + libra::Vector<3> after; + after[0] = 0.0; + after[1] = 1.0; + after[2] = 0.0; + + libra::Quaternion q(before, after); + + double theta_rad = -90 * libra::deg_to_rad; + EXPECT_NEAR(sin(theta_rad/2.0), q[0], 1e-5); EXPECT_NEAR(0.0, q[1], 1e-5); EXPECT_NEAR(0.0, q[2], 1e-5); - EXPECT_NEAR(1 / sqrt(2), q[3], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from two vectors: Y rotation + */ +TEST(Quaternion, ConstructorTwoVectorsY) { + libra::Vector<3> before; + before[0] = 0.0; + before[1] = 0.0; + before[2] = 1.0; + libra::Vector<3> after; + after[0] = 1.0; + after[1] = 0.0; + after[2] = 0.0; + + libra::Quaternion q(before, after); + + double theta_rad = 90 * libra::deg_to_rad; + EXPECT_NEAR(0.0, q[0], 1e-5); + EXPECT_NEAR(sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(0.0, q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); +} + +/** + * @brief Test for constructor from two vectors: Z rotation + */ +TEST(Quaternion, ConstructorTwoVectorsZ) { + libra::Vector<3> before; + before[0] = 1.0; + before[1] = 0.0; + before[2] = 0.0; + libra::Vector<3> after; + after[0] = 0.0; + after[1] = 1.0; + after[2] = 0.0; + + libra::Quaternion q(before, after); + + double theta_rad = 90 * libra::deg_to_rad; + EXPECT_NEAR(0.0, q[0], 1e-5); + EXPECT_NEAR(0.0, q[1], 1e-5); + EXPECT_NEAR(sin(theta_rad/2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); } From 00d832f6e32f3b9e3569691bb51d52d7f55d2f27 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 09:20:59 +0100 Subject: [PATCH 0949/1086] Add Normalize and Conjugate function --- src/library/math/test_quaternion.cpp | 38 ++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/src/library/math/test_quaternion.cpp b/src/library/math/test_quaternion.cpp index 74bf58e4f..6c300023a 100644 --- a/src/library/math/test_quaternion.cpp +++ b/src/library/math/test_quaternion.cpp @@ -186,3 +186,41 @@ TEST(Quaternion, ConstructorTwoVectorsZ) { EXPECT_NEAR(sin(theta_rad/2.0), q[2], 1e-5); EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); } + +/** + * @brief Test for Normalize + * @note TODO: Fix to nondestructive function + */ +TEST(Quaternion, Normalize) { + libra::Quaternion q(1.0, 1.0, 1.0, 1.0); + EXPECT_DOUBLE_EQ(1.0, q[0]); + EXPECT_DOUBLE_EQ(1.0, q[1]); + EXPECT_DOUBLE_EQ(1.0, q[2]); + EXPECT_DOUBLE_EQ(1.0, q[3]); + + q.Normalize(); + EXPECT_DOUBLE_EQ(0.5, q[0]); + EXPECT_DOUBLE_EQ(0.5, q[1]); + EXPECT_DOUBLE_EQ(0.5, q[2]); + EXPECT_DOUBLE_EQ(0.5, q[3]); +} + +/** + * @brief Test for Conjugate + */ +TEST(Quaternion, Conjugate) { + libra::Quaternion q(0.5, 0.5, 0.5, 0.5); + + libra::Quaternion q_conjugate = q.Conjugate(); + + // Check nondestructive function + EXPECT_DOUBLE_EQ(0.5, q[0]); + EXPECT_DOUBLE_EQ(0.5, q[1]); + EXPECT_DOUBLE_EQ(0.5, q[2]); + EXPECT_DOUBLE_EQ(0.5, q[3]); + + EXPECT_DOUBLE_EQ(-0.5, q_conjugate[0]); + EXPECT_DOUBLE_EQ(-0.5, q_conjugate[1]); + EXPECT_DOUBLE_EQ(-0.5, q_conjugate[2]); + EXPECT_DOUBLE_EQ(0.5, q_conjugate[3]); +} From 9d50d607833a382702382c7e429b282b3660c780 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 12:28:56 +0100 Subject: [PATCH 0950/1086] Add test for Vector --- CMakeLists.txt | 1 + src/library/math/test_vector.cpp | 449 +++++++++++++++++++++++++++++++ 2 files changed, 450 insertions(+) create mode 100644 src/library/math/test_vector.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 027d8f3c8..8bb4d55c0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -189,6 +189,7 @@ if(GOOGLE_TEST) set(TEST_PROJECT_NAME ${PROJECT_NAME}_TEST) set(TEST_FILES src/library/math/test_quaternion.cpp + src/library/math/test_vector.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/src/library/math/test_vector.cpp b/src/library/math/test_vector.cpp new file mode 100644 index 000000000..040130aa8 --- /dev/null +++ b/src/library/math/test_vector.cpp @@ -0,0 +1,449 @@ +/** + * @file test_quaternion.cpp + * @brief Test codes for Quaternion class with GoogleTest + */ +#include + +#include "constants.hpp" +#include "vector.hpp" + +/** + * @brief Test for constructor with number + */ +TEST(Vector, ConstructorWithNumber) { + const size_t N = 6; + double initialize_value = 2.0; + libra::Vector v(initialize_value); + + for (size_t i = 0; i < N; i++) { + EXPECT_DOUBLE_EQ(initialize_value, v[i]); + EXPECT_DOUBLE_EQ(initialize_value, v(i)); + } +} + +/** + * @brief Test for GetLength + */ +TEST(Vector, GetLength) { + const size_t N = 6; + libra::Vector v; + + EXPECT_EQ(N, v.GetLength()); +} + +/** + * @brief Test for operator+= + */ +TEST(Vector, OperatorPlusEqual) { + const size_t N = 6; + double initialize_value = 2.0; + libra::Vector v(initialize_value); + libra::Vector adding; + + for (size_t i = 0; i < N; i++) { + adding[i] = double(i); + } + + v += adding; + + for (size_t i = 0; i < N; i++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(double(i), adding[i]); + // Check added value + EXPECT_DOUBLE_EQ(initialize_value + double(i), v[i]); + } +} + +/** + * @brief Test for operator-= + */ +TEST(Vector, OperatorMinusEqual) { + const size_t N = 6; + double initialize_value = 2.0; + libra::Vector v(initialize_value); + libra::Vector subtracting; + + for (size_t i = 0; i < N; i++) { + subtracting[i] = double(i); + } + + v -= subtracting; + + for (size_t i = 0; i < N; i++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(double(i), subtracting[i]); + // Check subtracted value + EXPECT_DOUBLE_EQ(initialize_value - double(i), v[i]); + } +} + +/** + * @brief Test for operator*= + */ +TEST(Vector, OperatorMultiplyEqual) { + const size_t N = 6; + libra::Vector v; + double multiplying = 2.0; + + for (size_t i = 0; i < N; i++) { + v[i] = double(i); + } + + v *= multiplying; + + // Check nondestructive + EXPECT_DOUBLE_EQ(2.0, multiplying); + for (size_t i = 0; i < N; i++) { + // Check multiplied value + EXPECT_DOUBLE_EQ(multiplying * double(i), v[i]); + } +} + +/** + * @brief Test for operator/= + */ +TEST(Vector, OperatorDivideEqual) { + const size_t N = 6; + libra::Vector v; + double dividing = 3.0; + + for (size_t i = 0; i < N; i++) { + v[i] = double(i); + } + + v /= dividing; + + // Check nondestructive + EXPECT_DOUBLE_EQ(3.0, dividing); + for (size_t i = 0; i < N; i++) { + // Check divided value + EXPECT_DOUBLE_EQ(double(i)/dividing, v[i]); + } +} + +/** + * @brief Test for operator- + */ +TEST(Vector, OperatorNegative) { + const size_t N = 6; + libra::Vector v; + + for (size_t i = 0; i < N; i++) { + v[i] = double(i); + } + + libra::Vector v_negative = -v; + + for (size_t i = 0; i < N; i++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(double(i), v[i]); + // Check negative value + EXPECT_DOUBLE_EQ(double(i) * -1.0, v_negative[i]); + } +} + +/** + * @brief Test for FillUp + */ +TEST(Vector, FillUp) { + const size_t N = 6; + libra::Vector v; + + for (size_t i = 0; i < N; i++) { + v[i] = double(i); + } + + for (size_t i = 0; i < N; i++) { + EXPECT_DOUBLE_EQ(double(i), v[i]); + } + + double fill_up_value = 0.1; + FillUp(v, fill_up_value); + + for (size_t i = 0; i < N; i++) { + EXPECT_DOUBLE_EQ(fill_up_value, v[i]); + } +} + +/** + * @brief Test for operator+ + */ +TEST(Vector, OperatorPlus) { + const size_t N = 6; + double initialize_value = 2.0; + libra::Vector v(initialize_value); + libra::Vector adding; + + for (size_t i = 0; i < N; i++) { + adding[i] = double(i); + } + + libra::Vector added = v + adding; + + for (size_t i = 0; i < N; i++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(initialize_value, v[i]); + EXPECT_DOUBLE_EQ(double(i), adding[i]); + // Check added value + EXPECT_DOUBLE_EQ(initialize_value + adding[i], added[i]); + } +} + +/** + * @brief Test for operator- + */ +TEST(Vector, OperatorMinus) { + const size_t N = 6; + double initialize_value = 2.0; + libra::Vector v(initialize_value); + libra::Vector subtracting; + + for (size_t i = 0; i < N; i++) { + subtracting[i] = double(i); + } + + libra::Vector subtracted = v - subtracting; + + for (size_t i = 0; i < N; i++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(initialize_value, v[i]); + EXPECT_DOUBLE_EQ(double(i), subtracting[i]); + // Check subtracted value + EXPECT_DOUBLE_EQ(initialize_value - subtracting[i], subtracted[i]); + } +} + +/** + * @brief Test for InnerProduct + */ +TEST(Vector, InnerProduct) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + for (size_t i = 0; i < N; i++) { + a[i] = double(i + 1); + b[i] = 1.0 / double(i + 1); + } + + double result = InnerProduct(a, b); + EXPECT_DOUBLE_EQ(double(N), result); +} + +/** + * @brief Test for InnerProduct result zero + */ +TEST(Vector, InnerProductZero) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 1.0; + a[1] = 0.0; + a[2] = 0.0; + + b[0] = 0.0; + b[1] = 1.0; + b[2] = 0.0; + + double result = InnerProduct(a, b); + EXPECT_DOUBLE_EQ(0.0, result); +} + +/** + * @brief Test for OuterProduct result zero + */ +TEST(Vector, OuterProductZero) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 1.0; + a[1] = 0.0; + a[2] = 0.0; + + b[0] = 1.0; + b[1] = 0.0; + b[2] = 0.0; + + libra::Vector<3> result = OuterProduct(a, b); + + for (size_t i = 0; i < N; i++) { + EXPECT_DOUBLE_EQ(0.0, result[i]); + } +} + +/** + * @brief Test for OuterProduct result X axis + */ +TEST(Vector, OuterProductX) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 0.0; + a[1] = 0.0; + a[2] = 1.0; + + b[0] = 0.0; + b[1] = 1.0; + b[2] = 0.0; + + libra::Vector<3> result = OuterProduct(a, b); + + EXPECT_DOUBLE_EQ(-1.0, result[0]); + EXPECT_DOUBLE_EQ(0.0, result[1]); + EXPECT_DOUBLE_EQ(0.0, result[2]); +} + +/** + * @brief Test for OuterProduct result Y axis + */ +TEST(Vector, OuterProductY) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 0.0; + a[1] = 0.0; + a[2] = 1.0; + + b[0] = 1.0; + b[1] = 0.0; + b[2] = 0.0; + + libra::Vector<3> result = OuterProduct(a, b); + + EXPECT_DOUBLE_EQ(0.0, result[0]); + EXPECT_DOUBLE_EQ(1.0, result[1]); + EXPECT_DOUBLE_EQ(0.0, result[2]); +} + +/** + * @brief Test for OuterProduct result Z axis + */ +TEST(Vector, OuterProductZ) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 1.0; + a[1] = 0.0; + a[2] = 0.0; + + b[0] = 0.0; + b[1] = 1.0; + b[2] = 0.0; + + libra::Vector<3> result = OuterProduct(a, b); + + EXPECT_DOUBLE_EQ(0.0, result[0]); + EXPECT_DOUBLE_EQ(0.0, result[1]); + EXPECT_DOUBLE_EQ(1.0, result[2]); +} + +/** + * @brief Test for CalcNorm + */ +TEST(Vector, CalcNorm) { + const size_t N = 10; + libra::Vector v(1.0); + + double norm = CalcNorm(v); + + // Check nondestructive + for (size_t i = 0; i < N; i++) { + EXPECT_DOUBLE_EQ(1.0, v[i]); + } + + EXPECT_DOUBLE_EQ(sqrt(double(N)), norm); +} + +/** + * @brief Test for Normalize + */ +TEST(Vector, Normalize) { + const size_t N = 5; + libra::Vector v(1.0); + + libra::Vector normalized = Normalize(v); + + for (size_t i = 0; i < N; i++) { + // Check nondestructive (Currently, it is destructive) + EXPECT_DOUBLE_EQ(1.0/sqrt(double(N)), v[i]); + // Check nondestructive + EXPECT_DOUBLE_EQ(1.0/sqrt(double(N)), normalized[i]); + } +} + +/** + * @brief Test for CalcAngleTwoVectors result 90 deg + */ +TEST(Vector, CalcAngleTwoVectors90deg) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 1.0; + a[1] = 0.0; + a[2] = 0.0; + + b[0] = 0.0; + b[1] = 1.0; + b[2] = 0.0; + + double angle_rad = CalcAngleTwoVectors_rad(a, b); + + EXPECT_DOUBLE_EQ(90.0 * libra::deg_to_rad, angle_rad); +} + +/** + * @brief Test for CalcAngleTwoVectors result 0 deg + */ +TEST(Vector, CalcAngleTwoVectors0deg) { + const size_t N = 3; + libra::Vector a; + + a[0] = 1.0; + a[1] = 0.0; + a[2] = 0.0; + + double angle_rad = CalcAngleTwoVectors_rad(a, a); + + EXPECT_DOUBLE_EQ(0.0 * libra::deg_to_rad, angle_rad); +} + +/** + * @brief Test for CalcAngleTwoVectors result 45 deg + */ +TEST(Vector, CalcAngleTwoVectors45deg) { + const size_t N = 3; + libra::Vector a; + libra::Vector b; + + a[0] = 0.0; + a[1] = 1.0; + a[2] = 1.0; + + b[0] = 0.0; + b[1] = 1.0; + b[2] = 0.0; + + double angle_rad = CalcAngleTwoVectors_rad(a, b); + + EXPECT_DOUBLE_EQ(45.0 * libra::deg_to_rad, angle_rad); +} + +/** + * @brief Test for GenerateOrthogonalUnitVector + */ +TEST(Vector, GenerateOrthogonalUnitVector) { + const size_t N = 3; + libra::Vector a(1.0); + + libra::Vector b = GenerateOrthogonalUnitVector(a); + + double angle_rad = CalcAngleTwoVectors_rad(a, b); + + EXPECT_DOUBLE_EQ(90.0 * libra::deg_to_rad, angle_rad); +} From 6c5574b1329509481f6414e25764595074849f30 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 12:37:16 +0100 Subject: [PATCH 0951/1086] Add test for Matrix --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8bb4d55c0..eea3f8960 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -190,6 +190,7 @@ if(GOOGLE_TEST) set(TEST_FILES src/library/math/test_quaternion.cpp src/library/math/test_vector.cpp + src/library/math/test_matrix.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) From 91bbc829a68809962dbf8d6074cf4ade01b32ead Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 12:37:27 +0100 Subject: [PATCH 0952/1086] Add test for Matrix --- src/library/math/test_matrix.cpp | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) create mode 100644 src/library/math/test_matrix.cpp diff --git a/src/library/math/test_matrix.cpp b/src/library/math/test_matrix.cpp new file mode 100644 index 000000000..da9e4a41e --- /dev/null +++ b/src/library/math/test_matrix.cpp @@ -0,0 +1,25 @@ +/** + * @file test_quaternion.cpp + * @brief Test codes for Quaternion class with GoogleTest + */ +#include + +#include "constants.hpp" +#include "matrix.hpp" + +/** + * @brief Test for constructor with number + */ +TEST(Matrix, ConstructorWithNumber) { + const size_t R = 6; + const size_t C = 3; + double initialize_value = 2.0; + libra::Matrix m(initialize_value); + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + EXPECT_DOUBLE_EQ(initialize_value, m[r][c]); + EXPECT_DOUBLE_EQ(initialize_value, m(r, c)); + } + } +} From 12e18f13129c5738eb4f02e5d9d4a392a4b807ea Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:17:44 +0100 Subject: [PATCH 0953/1086] Add Matrix Test --- src/library/math/test_matrix.cpp | 426 +++++++++++++++++++++++++++++++ 1 file changed, 426 insertions(+) diff --git a/src/library/math/test_matrix.cpp b/src/library/math/test_matrix.cpp index da9e4a41e..0f18b2238 100644 --- a/src/library/math/test_matrix.cpp +++ b/src/library/math/test_matrix.cpp @@ -23,3 +23,429 @@ TEST(Matrix, ConstructorWithNumber) { } } } + +/** + * @brief Test for GetRowLength and GetColumnLength + */ +TEST(Matrix, GetLength) { + const size_t R = 6; + const size_t C = 3; + libra::Matrix m; + + EXPECT_EQ(R, m.GetRowLength()); + EXPECT_EQ(C, m.GetColumnLength()); +} + +/** + * @brief Test for operator+= + */ +TEST(Matrix, OperatorPlusEqual) { + const size_t R = 6; + const size_t C = 3; + double initialize_value = 2.0; + libra::Matrix m(initialize_value); + libra::Matrix adding; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + adding[r][c] = r * c; + } + } + + m += adding; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(r * c, adding[r][c]); + // Check result + EXPECT_DOUBLE_EQ(initialize_value + r * c, m[r][c]); + } + } +} + +/** + * @brief Test for operator-= + */ +TEST(Matrix, OperatorMinusEqual) { + const size_t R = 6; + const size_t C = 3; + double initialize_value = 2.0; + libra::Matrix m(initialize_value); + libra::Matrix subtracting; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + subtracting[r][c] = r * c; + } + } + + m -= subtracting; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(r * c, subtracting[r][c]); + // Check result + EXPECT_DOUBLE_EQ(initialize_value - r * c, m[r][c]); + } + } +} + +/** + * @brief Test for operator*= + */ +TEST(Matrix, OperatorMultiplyEqual) { + const size_t R = 6; + const size_t C = 3; + + libra::Matrix m; + double multiplying = 2.0; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + m[r][c] = r * c; + } + } + + m *= multiplying; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check result + EXPECT_DOUBLE_EQ(2.0 * r * c, m[r][c]); + } + } +} + +/** + * @brief Test for operator/= + */ +TEST(Matrix, OperatorDivideEqual) { + const size_t R = 6; + const size_t C = 3; + + libra::Matrix m; + double dividing = 2.0; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + m[r][c] = r * c; + } + } + + m /= dividing; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check result + EXPECT_DOUBLE_EQ(r * c / 2.0, m[r][c]); + } + } +} + +/** + * @brief Test for FillUp + */ +TEST(Matrix, FillUp) { + const size_t R = 6; + const size_t C = 3; + double value = 3.0; + + libra::Matrix m; + + FillUp(m, value); + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check result + EXPECT_DOUBLE_EQ(value, m[r][c]); + } + } +} + +/** + * @brief Test for CalcTrace + */ +TEST(Matrix, CalcTrace) { + const size_t N = 6; + libra::Matrix m; + + for (size_t r = 0; r < N; r++) { + for (size_t c = 0; c < N; c++) { + m[r][c] = r * c; + } + } + + double trace = CalcTrace(m); + + // Check nondestructive + for (size_t r = 0; r < N; r++) { + for (size_t c = 0; c < N; c++) { + EXPECT_DOUBLE_EQ(r * c, m[r][c]); + } + } + + // Check + double trace_check = 0.0; + for (size_t i = 0; i < N; i++) { + trace_check += i * i; + } + EXPECT_DOUBLE_EQ(trace_check, trace); +} + +/** + * @brief Test for operator+ + */ +TEST(Matrix, OperatorPlus) { + const size_t R = 6; + const size_t C = 3; + double initialize_value = -2.0; + libra::Matrix m(initialize_value); + libra::Matrix adding; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + adding[r][c] = r * c; + } + } + + libra::Matrix added = m + adding; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(initialize_value, m[r][c]); + EXPECT_DOUBLE_EQ(r * c, adding[r][c]); + // Check result + EXPECT_DOUBLE_EQ(initialize_value + r * c, added[r][c]); + } + } +} + +/** + * @brief Test for operator- + */ +TEST(Matrix, OperatorMinus) { + const size_t R = 6; + const size_t C = 3; + double initialize_value = 0.6; + libra::Matrix m(initialize_value); + libra::Matrix subtracting; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + subtracting[r][c] = r * c; + } + } + + libra::Matrix subtracted = m - subtracting; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(initialize_value, m[r][c]); + EXPECT_DOUBLE_EQ(r * c, subtracting[r][c]); + // Check result + EXPECT_DOUBLE_EQ(initialize_value - r * c, subtracted[r][c]); + } + } +} + +/** + * @brief Test for operator* scalar + */ +TEST(Matrix, OperatorMultiplyScalar) { + const size_t R = 6; + const size_t C = 3; + + libra::Matrix m; + double multiplying = 0.3; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + m[r][c] = r * c; + } + } + + libra::Matrix subtracted = multiplying * m; + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(r * c, m[r][c]); + // Check result + EXPECT_DOUBLE_EQ(0.3 * r * c, subtracted[r][c]); + } + } +} + +/** + * @brief Test for operator* Matrix + */ +TEST(Matrix, OperatorMultiplyMatrix) { + const size_t R = 2; + const size_t C = 3; + + libra::Matrix a; + libra::Matrix b; + + a[0][0] = 1.0; + a[0][1] = 2.0; + a[0][2] = 3.0; + a[1][0] = 4.0; + a[1][1] = 5.0; + a[1][2] = 6.0; + + b[0][0] = 1.0; + b[0][1] = 2.0; + b[1][0] = 3.0; + b[1][1] = 4.0; + b[2][0] = 5.0; + b[2][1] = 6.0; + + libra::Matrix result = a * b; + + EXPECT_DOUBLE_EQ(22.0, result[0][0]); + EXPECT_DOUBLE_EQ(28.0, result[0][1]); + EXPECT_DOUBLE_EQ(49.0, result[1][0]); + EXPECT_DOUBLE_EQ(64.0, result[1][1]); +} + +/** + * @brief Test for Transpose + */ +TEST(Matrix, Transpose) { + const size_t R = 6; + const size_t C = 3; + + libra::Matrix m; + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + m[r][c] = r * c; + } + } + + libra::Matrix transposed = Transpose(m); + + for (size_t r = 0; r < R; r++) { + for (size_t c = 0; c < C; c++) { + // Check nondestructive + EXPECT_DOUBLE_EQ(r * c, m[r][c]); + // Check result + EXPECT_DOUBLE_EQ(r * c, transposed[c][r]); + } + } +} + +/** + * @brief Test for Unitalize + */ +TEST(Matrix, Unitalize) { + const size_t N = 6; + + libra::Matrix m; + for (size_t r = 0; r < N; r++) { + for (size_t c = 0; c < N; c++) { + m[r][c] = r * c; + } + } + + libra::Matrix unitalized = Unitalize(m); + + for (size_t r = 0; r < N; r++) { + for (size_t c = 0; c < N; c++) { + // Check nondestructive (Currently, this is destructive) + if (r == c) { + EXPECT_DOUBLE_EQ(1.0, m[r][c]); + } else { + EXPECT_DOUBLE_EQ(0.0, m[r][c]); + } + // Check result + if (r == c) { + EXPECT_DOUBLE_EQ(1.0, unitalized[r][c]); + } else { + EXPECT_DOUBLE_EQ(0.0, unitalized[r][c]); + } + } + } +} + +/** + * @brief Test for MakeIdentityMatrix + */ +TEST(Matrix, MakeIdentityMatrix) { + const size_t N = 6; + + libra::Matrix m = libra::MakeIdentityMatrix(); + + for (size_t r = 0; r < N; r++) { + for (size_t c = 0; c < N; c++) { + if (r == c) { + EXPECT_DOUBLE_EQ(1.0, m[r][c]); + } else { + EXPECT_DOUBLE_EQ(0.0, m[r][c]); + } + } + } +} + +/** + * @brief Test for MakeRotationMatrixX + */ +TEST(Matrix, MakeRotationMatrixX) { + const size_t N = 3; + double theta_rad = -45.0 * libra::deg_to_rad; + + libra::Matrix m = libra::MakeRotationMatrixX(theta_rad); + + EXPECT_DOUBLE_EQ(1.0, m[0][0]); + EXPECT_DOUBLE_EQ(0.0, m[0][1]); + EXPECT_DOUBLE_EQ(0.0, m[0][2]); + EXPECT_DOUBLE_EQ(0.0, m[1][0]); + EXPECT_DOUBLE_EQ(cos(theta_rad), m[1][1]); + EXPECT_DOUBLE_EQ(sin(theta_rad), m[1][2]); + EXPECT_DOUBLE_EQ(0.0, m[2][0]); + EXPECT_DOUBLE_EQ(-sin(theta_rad), m[2][1]); + EXPECT_DOUBLE_EQ(cos(theta_rad), m[2][2]); +} + +/** + * @brief Test for MakeRotationMatrixY + */ +TEST(Matrix, MakeRotationMatrixY) { + const size_t N = 3; + double theta_rad = 120.0 * libra::deg_to_rad; + + libra::Matrix m = libra::MakeRotationMatrixY(theta_rad); + + EXPECT_DOUBLE_EQ(cos(theta_rad), m[0][0]); + EXPECT_DOUBLE_EQ(0.0, m[0][1]); + EXPECT_DOUBLE_EQ(-sin(theta_rad), m[0][2]); + EXPECT_DOUBLE_EQ(0.0, m[1][0]); + EXPECT_DOUBLE_EQ(1.0, m[1][1]); + EXPECT_DOUBLE_EQ(0.0, m[1][2]); + EXPECT_DOUBLE_EQ(sin(theta_rad), m[2][0]); + EXPECT_DOUBLE_EQ(0.0, m[2][1]); + EXPECT_DOUBLE_EQ(cos(theta_rad), m[2][2]); +} + +/** + * @brief Test for MakeRotationMatrixZ + */ +TEST(Matrix, MakeRotationMatrixZ) { + const size_t N = 3; + double theta_rad = 30.0 * libra::deg_to_rad; + + libra::Matrix m = libra::MakeRotationMatrixZ(theta_rad); + + EXPECT_DOUBLE_EQ(cos(theta_rad), m[0][0]); + EXPECT_DOUBLE_EQ(sin(theta_rad), m[0][1]); + EXPECT_DOUBLE_EQ(0.0, m[0][2]); + EXPECT_DOUBLE_EQ(-sin(theta_rad), m[1][0]); + EXPECT_DOUBLE_EQ(cos(theta_rad), m[1][1]); + EXPECT_DOUBLE_EQ(0.0, m[1][2]); + EXPECT_DOUBLE_EQ(0.0, m[2][0]); + EXPECT_DOUBLE_EQ(0.0, m[2][1]); + EXPECT_DOUBLE_EQ(1.0, m[2][2]); +} From 603dc2cddb9c1498f492e4863ba718d113494050 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:20:24 +0100 Subject: [PATCH 0954/1086] Add test file for MatrixVector --- CMakeLists.txt | 1 + src/library/math/test_matrix_vector.cpp | 14 ++++++++++++++ 2 files changed, 15 insertions(+) create mode 100644 src/library/math/test_matrix_vector.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index eea3f8960..0834fc95d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -191,6 +191,7 @@ if(GOOGLE_TEST) src/library/math/test_quaternion.cpp src/library/math/test_vector.cpp src/library/math/test_matrix.cpp + src/library/math/test_matrix_vector.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/src/library/math/test_matrix_vector.cpp b/src/library/math/test_matrix_vector.cpp new file mode 100644 index 000000000..060ad4e04 --- /dev/null +++ b/src/library/math/test_matrix_vector.cpp @@ -0,0 +1,14 @@ +/** + * @file test_quaternion.cpp + * @brief Test codes for Quaternion class with GoogleTest + */ +#include + +#include "constants.hpp" +#include "matrix_vector.hpp" + +/** + * @brief Test for Matrix * Vector + */ +TEST(MatrixVector, MultiplyMatrixVector) { +} From 08ade768f061fec88df1909f2afbdf6b3c14fe29 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:43:01 +0100 Subject: [PATCH 0955/1086] Add test for MatrixVector --- src/library/math/test_matrix_vector.cpp | 52 +++++++++++++++++++++++++ 1 file changed, 52 insertions(+) diff --git a/src/library/math/test_matrix_vector.cpp b/src/library/math/test_matrix_vector.cpp index 060ad4e04..af17b6fe2 100644 --- a/src/library/math/test_matrix_vector.cpp +++ b/src/library/math/test_matrix_vector.cpp @@ -11,4 +11,56 @@ * @brief Test for Matrix * Vector */ TEST(MatrixVector, MultiplyMatrixVector) { + const size_t R = 3; + const size_t C = 2; + + libra::Matrix m; + libra::Vector v; + + m[0][0] = 1.0; + m[0][1] = 2.0; + m[1][0] = -1.0; + m[1][1] = 0.0; + m[2][0] = 3.0; + m[2][1] = 1.0; + + v[0] = 7.0; + v[1] = 1.0; + + libra::Vector result = m * v; + + EXPECT_DOUBLE_EQ(9.0, result[0]); + EXPECT_DOUBLE_EQ(-7.0, result[1]); + EXPECT_DOUBLE_EQ(22.0, result[2]); +} + +/** + * @brief Test for CalcInverseMatrix + */ +TEST(MatrixVector, CalcInverseMatrix) { + const size_t N = 3; + + libra::Matrix m; + + m[0][0] = 1.0; + m[0][1] = 1.0; + m[0][2] = -1.0; + m[1][0] = -2.0; + m[1][1] = -1.0; + m[1][2] = 1.0; + m[2][0] = -1.0; + m[2][1] = -2.0; + m[2][2] = 1.0; + + libra::Matrix inverse = libra::CalcInverseMatrix(m); + + EXPECT_NEAR(-1.0, inverse[0][0], 1e-10); + EXPECT_NEAR(-1.0, inverse[0][1], 1e-10); + EXPECT_NEAR(0.0, inverse[0][2], 1e-10); + EXPECT_NEAR(-1.0, inverse[1][0], 1e-10); + EXPECT_NEAR(0.0, inverse[1][1], 1e-10); + EXPECT_NEAR(-1.0, inverse[1][2], 1e-10); + EXPECT_NEAR(-3.0, inverse[2][0], 1e-10); + EXPECT_NEAR(-1.0, inverse[2][1], 1e-10); + EXPECT_NEAR(-1.0, inverse[2][2], 1e-10); } From d4b9626b21df39a124069510261e262dcf0e3d3a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:51:55 +0100 Subject: [PATCH 0956/1086] Fix format --- src/library/math/test_quaternion.cpp | 48 ++++++++++++++-------------- src/library/math/test_vector.cpp | 10 +++--- 2 files changed, 29 insertions(+), 29 deletions(-) diff --git a/src/library/math/test_quaternion.cpp b/src/library/math/test_quaternion.cpp index 6c300023a..ecf45b2f3 100644 --- a/src/library/math/test_quaternion.cpp +++ b/src/library/math/test_quaternion.cpp @@ -4,8 +4,8 @@ */ #include -#include "quaternion.hpp" #include "constants.hpp" +#include "quaternion.hpp" /** * @brief Test for constructor from four numbers @@ -43,10 +43,10 @@ TEST(Quaternion, ConstructorAxisAndAngleX) { double theta_rad = 90 * libra::deg_to_rad; libra::Quaternion q(axis, theta_rad); - EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); - EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); - EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(axis[0] * sin(theta_rad / 2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad / 2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad / 2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -60,10 +60,10 @@ TEST(Quaternion, ConstructorAxisAndAngleY) { double theta_rad = 45 * libra::deg_to_rad; libra::Quaternion q(axis, theta_rad); - EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); - EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); - EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(axis[0] * sin(theta_rad / 2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad / 2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad / 2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -77,10 +77,10 @@ TEST(Quaternion, ConstructorAxisAndAngleZ) { double theta_rad = -60 * libra::deg_to_rad; libra::Quaternion q(axis, theta_rad); - EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); - EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); - EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(axis[0] * sin(theta_rad / 2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad / 2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad / 2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -94,10 +94,10 @@ TEST(Quaternion, ConstructorAxisAndAngleAll) { double theta_rad = 180 * libra::deg_to_rad; libra::Quaternion q(axis, theta_rad); - EXPECT_NEAR(axis[0] * sin(theta_rad/2.0), q[0], 1e-5); - EXPECT_NEAR(axis[1] * sin(theta_rad/2.0), q[1], 1e-5); - EXPECT_NEAR(axis[2] * sin(theta_rad/2.0), q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(axis[0] * sin(theta_rad / 2.0), q[0], 1e-5); + EXPECT_NEAR(axis[1] * sin(theta_rad / 2.0), q[1], 1e-5); + EXPECT_NEAR(axis[2] * sin(theta_rad / 2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -107,7 +107,7 @@ TEST(Quaternion, ConstructorTwoVectorsNoRotation) { libra::Vector<3> before; before[0] = 0.0; before[1] = 0.0; - before[2] = 2.0; // To check normalization + before[2] = 2.0; // To check normalization libra::Vector<3> after; after[0] = 0.0; after[1] = 0.0; @@ -137,10 +137,10 @@ TEST(Quaternion, ConstructorTwoVectorsX) { libra::Quaternion q(before, after); double theta_rad = -90 * libra::deg_to_rad; - EXPECT_NEAR(sin(theta_rad/2.0), q[0], 1e-5); + EXPECT_NEAR(sin(theta_rad / 2.0), q[0], 1e-5); EXPECT_NEAR(0.0, q[1], 1e-5); EXPECT_NEAR(0.0, q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -160,9 +160,9 @@ TEST(Quaternion, ConstructorTwoVectorsY) { double theta_rad = 90 * libra::deg_to_rad; EXPECT_NEAR(0.0, q[0], 1e-5); - EXPECT_NEAR(sin(theta_rad/2.0), q[1], 1e-5); + EXPECT_NEAR(sin(theta_rad / 2.0), q[1], 1e-5); EXPECT_NEAR(0.0, q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** @@ -183,8 +183,8 @@ TEST(Quaternion, ConstructorTwoVectorsZ) { double theta_rad = 90 * libra::deg_to_rad; EXPECT_NEAR(0.0, q[0], 1e-5); EXPECT_NEAR(0.0, q[1], 1e-5); - EXPECT_NEAR(sin(theta_rad/2.0), q[2], 1e-5); - EXPECT_NEAR(cos(theta_rad/2.0), q[3], 1e-5); + EXPECT_NEAR(sin(theta_rad / 2.0), q[2], 1e-5); + EXPECT_NEAR(cos(theta_rad / 2.0), q[3], 1e-5); } /** diff --git a/src/library/math/test_vector.cpp b/src/library/math/test_vector.cpp index 040130aa8..f8dd44f6e 100644 --- a/src/library/math/test_vector.cpp +++ b/src/library/math/test_vector.cpp @@ -117,7 +117,7 @@ TEST(Vector, OperatorDivideEqual) { EXPECT_DOUBLE_EQ(3.0, dividing); for (size_t i = 0; i < N; i++) { // Check divided value - EXPECT_DOUBLE_EQ(double(i)/dividing, v[i]); + EXPECT_DOUBLE_EQ(double(i) / dividing, v[i]); } } @@ -227,7 +227,7 @@ TEST(Vector, InnerProduct) { } double result = InnerProduct(a, b); - EXPECT_DOUBLE_EQ(double(N), result); + EXPECT_DOUBLE_EQ(double(N), result); } /** @@ -247,7 +247,7 @@ TEST(Vector, InnerProductZero) { b[2] = 0.0; double result = InnerProduct(a, b); - EXPECT_DOUBLE_EQ(0.0, result); + EXPECT_DOUBLE_EQ(0.0, result); } /** @@ -370,9 +370,9 @@ TEST(Vector, Normalize) { for (size_t i = 0; i < N; i++) { // Check nondestructive (Currently, it is destructive) - EXPECT_DOUBLE_EQ(1.0/sqrt(double(N)), v[i]); + EXPECT_DOUBLE_EQ(1.0 / sqrt(double(N)), v[i]); // Check nondestructive - EXPECT_DOUBLE_EQ(1.0/sqrt(double(N)), normalized[i]); + EXPECT_DOUBLE_EQ(1.0 / sqrt(double(N)), normalized[i]); } } From 338c43df2b081dfdfc41686279e2f056ad9fa443 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:56:28 +0100 Subject: [PATCH 0957/1086] Remove unnecessary Am2_ --- src/components/base/sensor.hpp | 6 +++--- src/components/base/sensor_template_functions.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index 67fe6019d..d747da344 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -25,14 +25,14 @@ class Sensor { * @param [in] scale_factor: Scale factor matrix * @param [in] range_to_const_c: Output range limit to be constant output value at the component frame * @param [in] range_to_zero_c: Output range limit to be zero output value at the component frame - * @param [in] bias_noise_c_Am2_: Constant bias noise at the component frame + * @param [in] bias_noise_c: Constant bias noise at the component frame * @param [in] normal_random_standard_deviation_c: Standard deviation of normal random noise at the component frame * @param [in] random_walk_step_width_s: Step width for random walk calculation [sec] * @param [in] random_walk_standard_deviation_c: Standard deviation of random wark at the component frame * @param [in] random_walk_limit_c: Limit of random walk at the component frame */ Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_noise_c_Am2_, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, + const libra::Vector& bias_noise_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c); /** * @fn ~Sensor @@ -53,7 +53,7 @@ class Sensor { libra::Matrix scale_factor_; //!< Scale factor matrix libra::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame libra::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame - libra::Vector bias_noise_c_Am2_; //!< Constant bias noise at the component frame + libra::Vector bias_noise_c_; //!< Constant bias noise at the component frame libra::NormalRand normal_random_noise_c_[N]; //!< Normal random RandomWalk random_walk_noise_c_; //!< Random Walk diff --git a/src/components/base/sensor_template_functions.hpp b/src/components/base/sensor_template_functions.hpp index db9ff2b2f..79c08a8e8 100644 --- a/src/components/base/sensor_template_functions.hpp +++ b/src/components/base/sensor_template_functions.hpp @@ -10,13 +10,13 @@ template Sensor::Sensor(const libra::Matrix& scale_factor, const libra::Vector& range_to_const_c, const libra::Vector& range_to_zero_c, - const libra::Vector& bias_noise_c_Am2_, const libra::Vector& normal_random_standard_deviation_c, + const libra::Vector& bias_noise_c, const libra::Vector& normal_random_standard_deviation_c, const double random_walk_step_width_s, const libra::Vector& random_walk_standard_deviation_c, const libra::Vector& random_walk_limit_c) : scale_factor_(scale_factor), range_to_const_c_(range_to_const_c), range_to_zero_c_(range_to_zero_c), - bias_noise_c_Am2_(bias_noise_c_Am2_), + bias_noise_c_(bias_noise_c), random_walk_noise_c_(random_walk_step_width_s, random_walk_standard_deviation_c, random_walk_limit_c) { for (size_t i = 0; i < N; i++) { normal_random_noise_c_[i].SetParameters(0.0, normal_random_standard_deviation_c[i], global_randomization.MakeSeed()); @@ -31,7 +31,7 @@ template libra::Vector Sensor::Measure(const libra::Vector true_value_c) { libra::Vector calc_value_c; calc_value_c = scale_factor_ * true_value_c; - calc_value_c += bias_noise_c_Am2_; + calc_value_c += bias_noise_c_; for (size_t i = 0; i < N; ++i) { calc_value_c[i] += random_walk_noise_c_[i]; calc_value_c[i] += normal_random_noise_c_[i]; From ae20057a5a16ac224d51a5244860dd494354b988 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 14:58:46 +0100 Subject: [PATCH 0958/1086] Fix is positive edge --- .../examples/example_serial_communication_with_obc.cpp | 4 ++-- .../examples/example_serial_communication_with_obc.hpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index d9d9c0f31..e79468825 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -51,6 +51,6 @@ void ExampleSerialCommunicationWithObc::MainRoutine(const int time_count) { SendTelemetry(0); } -void ExampleSerialCommunicationWithObc::GpioStateChanged(int port_id, bool isPosedge) { - printf("interrupted. portid = %d, isPosedge = %d./n", port_id, isPosedge); +void ExampleSerialCommunicationWithObc::GpioStateChanged(int port_id, bool is_positive_edge) { + printf("interrupted. portid = %d, isPosedge = %d./n", port_id, is_positive_edge); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 7b86c8833..89bcee035 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -64,7 +64,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @fn GpioStateChanged * @brief Interrupt function for GPIO */ - void GpioStateChanged(int port_id, bool isPosedge); + void GpioStateChanged(int port_id, bool is_positive_edge); private: const static int kMaxMemoryLength = 100; //!< Maximum memory length From 8f14bddf90ac54a8db9e15ad79945705f5cb24b3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 15:01:21 +0100 Subject: [PATCH 0959/1086] Fix Cmd to Command --- src/components/ports/hils_i2c_target_port.cpp | 10 +++++----- src/components/ports/hils_i2c_target_port.hpp | 10 +++++----- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/components/ports/hils_i2c_target_port.cpp b/src/components/ports/hils_i2c_target_port.cpp index 73d7e38a4..c4797e31e 100644 --- a/src/components/ports/hils_i2c_target_port.cpp +++ b/src/components/ports/hils_i2c_target_port.cpp @@ -20,7 +20,7 @@ void HilsI2cTargetPort::RegisterDevice() { for (unsigned char i = 0; i < max_register_number_; i++) { device_registers_[i] = 0x00; } - for (unsigned char i = 0; i < kDefaultCmdSize; i++) { + for (unsigned char i = 0; i < kDefaultCommandSize; i++) { command_buffer_[i] = 0x00; } } @@ -46,7 +46,7 @@ unsigned char HilsI2cTargetPort::ReadRegister(const unsigned char register_addre } int HilsI2cTargetPort::ReadCommand(unsigned char* rx_data, const unsigned int length) { - if (length > kDefaultCmdSize) { + if (length > kDefaultCommandSize) { return -1; } for (unsigned char i = 0; i < length; i++) { @@ -57,10 +57,10 @@ int HilsI2cTargetPort::ReadCommand(unsigned char* rx_data, const unsigned int le int HilsI2cTargetPort::Receive() // from I2C-USB Target converter { - unsigned char rx_buf[kDefaultCmdSize]; + unsigned char rx_buf[kDefaultCommandSize]; if (GetBytesToRead() <= 0) return -1; // No bytes were available to read. - int received_bytes = ReadRx(rx_buf, 0, kDefaultCmdSize); - if (received_bytes > kDefaultCmdSize) return -1; + int received_bytes = ReadRx(rx_buf, 0, kDefaultCommandSize); + if (received_bytes > kDefaultCommandSize) return -1; #ifdef HILS_I2C_TARGET_PORT_SHOW_DEBUG_DATA for (int i = 0; i < received_bytes; i++) { printf("%02x ", rx_buf[i]); diff --git a/src/components/ports/hils_i2c_target_port.hpp b/src/components/ports/hils_i2c_target_port.hpp index ca34f1ee0..a9e2c8663 100644 --- a/src/components/ports/hils_i2c_target_port.hpp +++ b/src/components/ports/hils_i2c_target_port.hpp @@ -93,11 +93,11 @@ class HilsI2cTargetPort : public HilsUartPort { int GetStoredFrameCounter(); private: - const unsigned int kDefaultCmdSize = 0xff; //!< Default command size - const unsigned int kDefaultTxSize = 0xff; //!< Default TX size - unsigned char max_register_number_ = 0xff; //!< Maximum register number - unsigned char saved_register_address_ = 0x00; //!< Saved register address - unsigned int stored_frame_counter_ = 0; //!< Send a few frames of telemetry to the converter in advance. + const unsigned int kDefaultCommandSize = 0xff; //!< Default command size + const unsigned int kDefaultTxSize = 0xff; //!< Default TX size + unsigned char max_register_number_ = 0xff; //!< Maximum register number + unsigned char saved_register_address_ = 0x00; //!< Saved register address + unsigned int stored_frame_counter_ = 0; //!< Send a few frames of telemetry to the converter in advance. /** @brief Device register: < register address, value> **/ std::map device_registers_; From 26e047c5596a394a16186d2ecc79d3434451dd68 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 15:02:01 +0100 Subject: [PATCH 0960/1086] Fix function name in comments --- src/components/real/aocs/sun_sensor.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index f6898a99c..81b6ddd14 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -128,7 +128,7 @@ class SunSensor : public Component, public ILoggable { */ double TanRange(double x); /** - * @fn TanRange + * @fn Initialize * @brief Clip angle as tangent range * @param [in] random_noise_standard_deviation_rad: Standard deviation of normal random noise in the component frame [rad] * @param [in] bias_noise_standard_deviation_rad: Standard deviation of normal random noise for bias in the component frame [rad] From 3d0e357d804a2623a1bcc9fbb21438dcd5afffa7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 15:06:34 +0100 Subject: [PATCH 0961/1086] Add comments for communication abbreviation --- src/components/real/communication/antenna.hpp | 2 +- src/components/real/communication/ground_station_calculator.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 8620e8fc1..dc59be475 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -135,7 +135,7 @@ class Antenna { // Rx info double rx_system_noise_temperature_K_; //!< Receive system noise temperature [K] AntennaParameters rx_parameters_; //!< RX parameters - double rx_gt_dBK_; //!< Receive G/T [dB/K] + double rx_gt_dBK_; //!< Receive G/T(Gain/Temperature) [dB/K] /** * @fn CalcAntennaGain diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index cf8eee347..ab4ddb01b 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -89,7 +89,7 @@ class GroundStationCalculator : public ILoggable { double loss_atmosphere_dB_; //!< Loss atmosphere [dB] double loss_rainfall_dB_; //!< Loss rainfall [dB] double loss_others_dB_; //!< Loss others [dB] - double ebn0_dB_; //!< EbN0 [dB] + double ebn0_dB_; //!< EbN0 (Energy per bit to Noise density ratio) [dB] double hardware_deterioration_dB_; //!< Hardware deterioration [dB] double coding_gain_dB_; //!< Coding gain [dB] // Variables From 8e565a23c325481fe62f253fb06ca610eac9bb9a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 15:08:37 +0100 Subject: [PATCH 0962/1086] Fix initialize key frame --- .../initialize_ground_station_calculator.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/components/real/communication/initialize_ground_station_calculator.cpp b/src/components/real/communication/initialize_ground_station_calculator.cpp index 5573e84b1..b5a6da536 100644 --- a/src/components/real/communication/initialize_ground_station_calculator.cpp +++ b/src/components/real/communication/initialize_ground_station_calculator.cpp @@ -15,14 +15,14 @@ GroundStationCalculator InitGsCalculator(const std::string file_name) { char Section[30] = "GROUND_STATION_CALCULATOR"; - double loss_polarization_dB = gs_conf.ReadDouble(Section, "loss_polarization_dB_dB"); - double loss_atmosphere_dB = gs_conf.ReadDouble(Section, "loss_atmosphere_dB_dB"); - double loss_rainfall_dB = gs_conf.ReadDouble(Section, "loss_rainfall_dB_dB"); - double loss_others_dB = gs_conf.ReadDouble(Section, "loss_others_dB_dB"); + double loss_polarization_dB = gs_conf.ReadDouble(Section, "loss_polarization_dB"); + double loss_atmosphere_dB = gs_conf.ReadDouble(Section, "loss_atmosphere_dB"); + double loss_rainfall_dB = gs_conf.ReadDouble(Section, "loss_rainfall_dB"); + double loss_others_dB = gs_conf.ReadDouble(Section, "loss_others_dB"); double ebn0_dB = gs_conf.ReadDouble(Section, "ebn0_dB"); - double hardware_deterioration_dB = gs_conf.ReadDouble(Section, "hardware_deterioration_dB_dB"); - double coding_gain_dB = gs_conf.ReadDouble(Section, "coding_gain_dB_dB"); - double margin_requirement_dB = gs_conf.ReadDouble(Section, "margin_requirement_dBuirement_dB"); + double hardware_deterioration_dB = gs_conf.ReadDouble(Section, "hardware_deterioration_dB"); + double coding_gain_dB = gs_conf.ReadDouble(Section, "coding_gain_dB"); + double margin_requirement_dB = gs_conf.ReadDouble(Section, "margin_requirement_dB"); double downlink_bitrate_bps = gs_conf.ReadDouble(Section, "downlink_bitrate_bps"); GroundStationCalculator gs_calculator(loss_polarization_dB, loss_atmosphere_dB, loss_rainfall_dB, loss_others_dB, ebn0_dB, From d02cd3dd2b4315d69f5c2ec4651ad2e438505aad Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 16:46:20 +0100 Subject: [PATCH 0963/1086] Add test for quaternion --- src/library/math/test_quaternion.cpp | 233 +++++++++++++++++++++++++++ 1 file changed, 233 insertions(+) diff --git a/src/library/math/test_quaternion.cpp b/src/library/math/test_quaternion.cpp index ecf45b2f3..12053cca2 100644 --- a/src/library/math/test_quaternion.cpp +++ b/src/library/math/test_quaternion.cpp @@ -224,3 +224,236 @@ TEST(Quaternion, Conjugate) { EXPECT_DOUBLE_EQ(-0.5, q_conjugate[2]); EXPECT_DOUBLE_EQ(0.5, q_conjugate[3]); } + +/** + * @brief Test for ConvertToDcm Y rotation + */ +TEST(Quaternion, ConvertToDcmY) { + libra::Quaternion q(0.0, 1.0, 0.0, 1.0); + q.Normalize(); + + libra::Matrix<3, 3> dcm = q.ConvertToDcm(); + + // Check nondestructive function + EXPECT_DOUBLE_EQ(0.0, q[0]); + EXPECT_DOUBLE_EQ(1.0 / sqrt(2.0), q[1]); + EXPECT_DOUBLE_EQ(0.0, q[2]); + EXPECT_DOUBLE_EQ(1.0 / sqrt(2.0), q[3]); + + // Check nondestructive function + const double accuracy = 1.0e-7; + EXPECT_NEAR(0.0, dcm[0][0], accuracy); + EXPECT_NEAR(0.0, dcm[0][1], accuracy); + EXPECT_NEAR(-1.0, dcm[0][2], accuracy); + EXPECT_NEAR(0.0, dcm[1][0], accuracy); + EXPECT_NEAR(1.0, dcm[1][1], accuracy); + EXPECT_NEAR(0.0, dcm[1][2], accuracy); + EXPECT_NEAR(1.0, dcm[2][0], accuracy); + EXPECT_NEAR(0.0, dcm[2][1], accuracy); + EXPECT_NEAR(0.0, dcm[2][2], accuracy); + + // Inverse Conversion + libra::Quaternion q_from_dcm = libra::Quaternion::ConvertFromDcm(dcm); + for (size_t i = 0; i < 4; i++) { + EXPECT_NEAR(q[i], q_from_dcm[i], accuracy); + } +} + +/** + * @brief Test for ConvertToDcm + */ +TEST(Quaternion, ConvertToDcm) { + libra::Quaternion q(0.5, 0.3, 0.1, 1.0); + q.Normalize(); + + libra::Matrix<3, 3> dcm = q.ConvertToDcm(); + + // Check nondestructive function + const double accuracy = 1.0e-5; + EXPECT_NEAR(0.8518519, dcm[0][0], accuracy); + EXPECT_NEAR(0.3703704, dcm[0][1], accuracy); + EXPECT_NEAR(-0.3703704, dcm[0][2], accuracy); + EXPECT_NEAR(0.0740741, dcm[1][0], accuracy); + EXPECT_NEAR(0.6148148, dcm[1][1], accuracy); + EXPECT_NEAR(0.7851851, dcm[1][2], accuracy); + EXPECT_NEAR(0.5185185, dcm[2][0], accuracy); + EXPECT_NEAR(-0.696296, dcm[2][1], accuracy); + EXPECT_NEAR(0.4962963, dcm[2][2], accuracy); + + // Inverse Conversion + libra::Quaternion q_from_dcm = libra::Quaternion::ConvertFromDcm(dcm); + for (size_t i = 0; i < 4; i++) { + EXPECT_NEAR(q[i], q_from_dcm[i], accuracy); + } +} + +/** + * @brief Test for ConvertToEuler X rotation + */ +TEST(Quaternion, ConvertToEulerX) { + libra::Quaternion q(1.0, 0.0, 0.0, 1.0); + q.Normalize(); + + libra::Vector<3> euler = q.ConvertToEuler(); + + // Check nondestructive function + EXPECT_DOUBLE_EQ(1.0 / sqrt(2.0), q[0]); + EXPECT_DOUBLE_EQ(0.0, q[1]); + EXPECT_DOUBLE_EQ(0.0, q[2]); + EXPECT_DOUBLE_EQ(1.0 / sqrt(2.0), q[3]); + + // Check nondestructive function + const double accuracy = 1.0e-7; + EXPECT_NEAR(90 * libra::deg_to_rad, euler[0], accuracy); + EXPECT_NEAR(0.0, euler[1], accuracy); + EXPECT_NEAR(0.0, euler[2], accuracy); + + // Inverse Conversion + libra::Quaternion q_from_euler = libra::Quaternion::ConvertFromEuler(euler); + for (size_t i = 0; i < 4; i++) { + EXPECT_NEAR(q[i], q_from_euler[i], accuracy); + } +} + +/** + * @brief Test for ConvertToEuler + */ +TEST(Quaternion, ConvertToEuler) { + libra::Quaternion q(0.5, 0.3, 0.1, 1.0); + q.Normalize(); + + libra::Vector<3> euler = q.ConvertToEuler(); + + // Check nondestructive function + const double accuracy = 1.0e-7; + EXPECT_NEAR(1.00712520, euler[0], accuracy); + EXPECT_NEAR(0.37940772, euler[1], accuracy); + EXPECT_NEAR(0.41012734, euler[2], accuracy); + + // Inverse Conversion + libra::Quaternion q_from_euler = libra::Quaternion::ConvertFromEuler(euler); + for (size_t i = 0; i < 4; i++) { + EXPECT_NEAR(q[i], q_from_euler[i], accuracy); + } +} + +/** + * @brief Test for FrameConversion Z rotation + */ +TEST(Quaternion, FrameConversionZ) { + libra::Quaternion q(0.0, 0.0, 1.0, 1.0); + q.Normalize(); + + libra::Vector<3> v; + v[0] = 1.0; + v[1] = 0.0; + v[2] = 0.0; + + libra::Vector<3> v_frame_conv = q.FrameConversion(v); + + const double accuracy = 1.0e-7; + EXPECT_NEAR(0.0, v_frame_conv[0], accuracy); + EXPECT_NEAR(-1.0, v_frame_conv[1], accuracy); + EXPECT_NEAR(0.0, v_frame_conv[2], accuracy); + + libra::Vector<3> v_frame_conv_inv = q.InverseFrameConversion(v_frame_conv); + + for (size_t i = 0; i < 3; i++) { + EXPECT_NEAR(v[i], v_frame_conv_inv[i], accuracy); + } +} + +/** + * @brief Test for FrameConversion + */ +TEST(Quaternion, FrameConversion) { + libra::Quaternion q(0.5, 0.3, 0.1, 1.0); + q.Normalize(); + libra::Vector<3> v; + v[0] = 1.0; + v[1] = 0.0; + v[2] = 0.0; + + libra::Vector<3> v_frame_conv = q.FrameConversion(v); + libra::Vector<3> v_frame_conv_inv = q.InverseFrameConversion(v_frame_conv); + + const double accuracy = 1.0e-7; + for (size_t i = 0; i < 3; i++) { + EXPECT_NEAR(v[i], v_frame_conv_inv[i], accuracy); + } +} + +/** + * @brief Test for ConvertToVector + */ +TEST(Quaternion, ConvertToVector) { + libra::Quaternion q(0.5, 0.3, 0.1, 1.0); + + libra::Vector<4> v = q.ConvertToVector(); + + for (size_t i = 0; i < 4; i++) { + EXPECT_DOUBLE_EQ(q[i], v[i]); + } +} + +/** + * @brief Test for operator+ + */ +TEST(Quaternion, OperatorPlus) { + libra::Quaternion q1(0.5, 0.3, 0.1, 1.0); + libra::Quaternion q2(-0.3, 0.1, -1.0, 0.4); + + libra::Quaternion result = q1 + q2; + + EXPECT_DOUBLE_EQ(0.2, result[0]); + EXPECT_DOUBLE_EQ(0.4, result[1]); + EXPECT_DOUBLE_EQ(-0.9, result[2]); + EXPECT_DOUBLE_EQ(1.4, result[3]); +} + +/** + * @brief Test for operator- + */ +TEST(Quaternion, OperatorMinus) { + libra::Quaternion q1(0.5, 0.3, 0.1, 1.0); + libra::Quaternion q2(-0.3, 0.1, -1.0, 0.4); + + libra::Quaternion result = q1 - q2; + + EXPECT_DOUBLE_EQ(0.8, result[0]); + EXPECT_DOUBLE_EQ(0.2, result[1]); + EXPECT_DOUBLE_EQ(1.1, result[2]); + EXPECT_DOUBLE_EQ(0.6, result[3]); +} + +/** + * @brief Test for operator* quaternion + */ +TEST(Quaternion, OperatorQuaternionMultiply) { + libra::Quaternion q1(0.289271, -0.576012, -0.420972, 0.638212); + libra::Quaternion q2(-0.0821846, 0.501761, 0.721995, -0.469259); + + libra::Quaternion result = q1 * q2; + + const double accuracy = 1.0e-7; + EXPECT_NEAR(-0.3928446703722, result[0], accuracy); + EXPECT_NEAR(0.4162739062262, result[1], accuracy); + EXPECT_NEAR(0.7561363631038, result[2], accuracy); + EXPECT_NEAR(0.3172469327906, result[3], accuracy); +} + +/** + * @brief Test for operator* scalar + */ +TEST(Quaternion, OperatorScalarMultiply) { + libra::Quaternion q(0.289271, -0.576012, -0.420972, 0.638212); + double scalar = 2.3; + + libra::Quaternion result = scalar * q; + + const double accuracy = 1.0e-7; + EXPECT_NEAR(q[0] * 2.3, result[0], accuracy); + EXPECT_NEAR(q[1] * 2.3, result[1], accuracy); + EXPECT_NEAR(q[2] * 2.3, result[2], accuracy); + EXPECT_NEAR(q[3] * 2.3, result[3], accuracy); +} From a2d277f7f9e75a474b4058875ad15b07fc8885b0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 18:23:27 +0100 Subject: [PATCH 0964/1086] Add s2e_math test --- CMakeLists.txt | 1 + src/library/math/test_s2e_math.cpp | 27 +++++++++++++++++++++++++++ 2 files changed, 28 insertions(+) create mode 100644 src/library/math/test_s2e_math.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 0834fc95d..e6075c11d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -192,6 +192,7 @@ if(GOOGLE_TEST) src/library/math/test_vector.cpp src/library/math/test_matrix.cpp src/library/math/test_matrix_vector.cpp + src/library/math/test_s2e_math.cpp ) add_executable(${TEST_PROJECT_NAME} ${TEST_FILES}) target_link_libraries(${TEST_PROJECT_NAME} gtest gtest_main) diff --git a/src/library/math/test_s2e_math.cpp b/src/library/math/test_s2e_math.cpp new file mode 100644 index 000000000..7def22225 --- /dev/null +++ b/src/library/math/test_s2e_math.cpp @@ -0,0 +1,27 @@ +/** + * @file test_quaternion.cpp + * @brief Test codes for Quaternion class with GoogleTest + */ +#include + +#include "constants.hpp" +#include "s2e_math.hpp" + +/** + * @brief Test for constructor with number + */ +TEST(S2eMath, WrapTo2Pi) { + const double accuracy = 1.0e-7; + + double input_angle_rad = 0.0; + double wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); + EXPECT_NEAR(0.0, wrapped_angle_rad, accuracy); + + input_angle_rad = -1.0e-5; + wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); + EXPECT_NEAR(libra::tau + input_angle_rad, wrapped_angle_rad, accuracy); + + input_angle_rad = libra::tau + 1.0e-5; + wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); + EXPECT_NEAR(1.0e-5, wrapped_angle_rad, accuracy); +} From 3ef0fd9efd70788852a2714e218fd409deeb5f0c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 18:25:57 +0100 Subject: [PATCH 0965/1086] Fix format --- src/library/math/test_s2e_math.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/library/math/test_s2e_math.cpp b/src/library/math/test_s2e_math.cpp index 7def22225..08989145a 100644 --- a/src/library/math/test_s2e_math.cpp +++ b/src/library/math/test_s2e_math.cpp @@ -12,7 +12,7 @@ */ TEST(S2eMath, WrapTo2Pi) { const double accuracy = 1.0e-7; - + double input_angle_rad = 0.0; double wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); EXPECT_NEAR(0.0, wrapped_angle_rad, accuracy); From dddd0f7dff50cdcf3a189791d5d14ab7a75f24fe Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 18:32:52 +0100 Subject: [PATCH 0966/1086] Add test input = 20 pi for Wrap2Pi --- src/library/math/test_s2e_math.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/library/math/test_s2e_math.cpp b/src/library/math/test_s2e_math.cpp index 08989145a..bf5b60fca 100644 --- a/src/library/math/test_s2e_math.cpp +++ b/src/library/math/test_s2e_math.cpp @@ -24,4 +24,8 @@ TEST(S2eMath, WrapTo2Pi) { input_angle_rad = libra::tau + 1.0e-5; wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); EXPECT_NEAR(1.0e-5, wrapped_angle_rad, accuracy); + + input_angle_rad = 10 * libra::tau + 1.0e-5; + wrapped_angle_rad = libra::WrapTo2Pi(input_angle_rad); + EXPECT_NEAR(1.0e-5, wrapped_angle_rad, accuracy); } From 2e68284c8b22c2ce81f907f3e8dd60175c9685f0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:17:10 +0100 Subject: [PATCH 0967/1086] Add plot for inertial celestial body orbit --- scripts/Plot/plot_celestial_orbit_i.py | 100 +++++++++++++++++++++++++ 1 file changed, 100 insertions(+) create mode 100644 scripts/Plot/plot_celestial_orbit_i.py diff --git a/scripts/Plot/plot_celestial_orbit_i.py b/scripts/Plot/plot_celestial_orbit_i.py new file mode 100644 index 000000000..4566ef724 --- /dev/null +++ b/scripts/Plot/plot_celestial_orbit_i.py @@ -0,0 +1,100 @@ +# +# Plot celestial body orbit in the inertial frame +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +sun_position_i_m = read_3d_vector_from_csv(read_file_name, 'sun_position_i', 'm') +sun_velocity_i_m_s = read_3d_vector_from_csv(read_file_name, 'sun_velocity_i', 'm/s') +moon_position_i_m = read_3d_vector_from_csv(read_file_name, 'moon_position_i', 'm') +moon_velocity_i_m_s = read_3d_vector_from_csv(read_file_name, 'moon_velocity_i', 'm/s') + +# +# Plot +# +plt.figure(0) +plt.plot(time[0], sun_position_i_m[0], marker=".", c="red", label="X") +plt.plot(time[0], sun_position_i_m[1], marker=".", c="green", label="Y") +plt.plot(time[0], sun_position_i_m[2], marker=".", c="blue", label="Z") +plt.title("Sun Position @ the inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Position [m]") +plt.legend() + +plt.figure(1) +plt.plot(time[0], sun_velocity_i_m_s[0], marker=".", c="red", label="X") +plt.plot(time[0], sun_velocity_i_m_s[1], marker=".", c="green", label="Y") +plt.plot(time[0], sun_velocity_i_m_s[2], marker=".", c="blue", label="Z") +plt.title("Sun Velocity @ the inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Velocity [m]") +plt.legend() + +plt.figure(2) +plt.plot(time[0], moon_position_i_m[0], marker=".", c="red", label="X") +plt.plot(time[0], moon_position_i_m[1], marker=".", c="green", label="Y") +plt.plot(time[0], moon_position_i_m[2], marker=".", c="blue", label="Z") +plt.title("Moon Position @ the inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Position [m]") +plt.legend() + +plt.figure(3) +plt.plot(time[0], moon_velocity_i_m_s[0], marker=".", c="red", label="X") +plt.plot(time[0], moon_velocity_i_m_s[1], marker=".", c="green", label="Y") +plt.plot(time[0], moon_velocity_i_m_s[2], marker=".", c="blue", label="Z") +plt.title("Moon Velocity @ the inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Velocity [m]") +plt.legend() + + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_disturbance_torque.png") # save last figure only +else: + plt.show() From 551264b7eeec41b8f13ab5f3781dbac7f2a3eca5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:19:56 +0100 Subject: [PATCH 0968/1086] Fix file name --- scripts/Plot/plot_celestial_orbit_i.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/Plot/plot_celestial_orbit_i.py b/scripts/Plot/plot_celestial_orbit_i.py index 4566ef724..a26bff25c 100644 --- a/scripts/Plot/plot_celestial_orbit_i.py +++ b/scripts/Plot/plot_celestial_orbit_i.py @@ -95,6 +95,6 @@ # Data save if args.no_gui: - plt.savefig(read_file_tag + "_disturbance_torque.png") # save last figure only + plt.savefig(read_file_tag + "_celestial_orbit_i.png") # save last figure only else: plt.show() From 8f8de156219e9c1c7b2eea5b1e118bcb7ca33573 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:24:02 +0100 Subject: [PATCH 0969/1086] Add plot for geomagnetic field --- scripts/Plot/plot_geomagnetic_field.py | 79 ++++++++++++++++++++++++++ 1 file changed, 79 insertions(+) create mode 100644 scripts/Plot/plot_geomagnetic_field.py diff --git a/scripts/Plot/plot_geomagnetic_field.py b/scripts/Plot/plot_geomagnetic_field.py new file mode 100644 index 000000000..f11940874 --- /dev/null +++ b/scripts/Plot/plot_geomagnetic_field.py @@ -0,0 +1,79 @@ +# +# Plot geomaginetic field at the spacecraft position +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +geomagnetic_field_at_spacecraft_position_i_nT = read_3d_vector_from_csv(read_file_name, 'geomagnetic_field_at_spacecraft_position_i', 'nT') +geomagnetic_field_at_spacecraft_position_b_nT = read_3d_vector_from_csv(read_file_name, 'geomagnetic_field_at_spacecraft_position_b', 'nT') + +# +# Plot +# +plt.figure(0) +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_i_nT[0], marker=".", c="red", label="X") +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_i_nT[1], marker=".", c="green", label="Y") +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_i_nT[2], marker=".", c="blue", label="Z") +plt.title("Geomagnetic Field at the spacecraft position @ the inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Magnetic Field [nT]") +plt.legend() + +plt.figure(1) +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_b_nT[0], marker=".", c="red", label="X") +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_b_nT[1], marker=".", c="green", label="Y") +plt.plot(time[0], geomagnetic_field_at_spacecraft_position_b_nT[2], marker=".", c="blue", label="Z") +plt.title("Geomagnetic Field at the spacecraft position @ the body frame") +plt.xlabel("Time [s]") +plt.ylabel("Magnetic Field [nT]") +plt.legend() + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_geomagnetic_field.png") # save last figure only +else: + plt.show() From 99049ab7a016df8773cde6818e30107a79783b45 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:40:57 +0100 Subject: [PATCH 0970/1086] Add plot for solar radiation pressure environment --- .../Plot/plot_solar_radiation_environment.py | 75 +++++++++++++++++++ 1 file changed, 75 insertions(+) create mode 100644 scripts/Plot/plot_solar_radiation_environment.py diff --git a/scripts/Plot/plot_solar_radiation_environment.py b/scripts/Plot/plot_solar_radiation_environment.py new file mode 100644 index 000000000..11b67b12a --- /dev/null +++ b/scripts/Plot/plot_solar_radiation_environment.py @@ -0,0 +1,75 @@ +# +# Plot solar radiation environment at the spacecraft position +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +solar_radiation_pressure_at_spacecraft_position_N_m2 = read_scalar_from_csv(read_file_name, 'solar_radiation_pressure_at_spacecraft_position[N/m2]') +shadow_coefficient_at_spacecraft_position = read_scalar_from_csv(read_file_name, 'shadow_coefficient_at_spacecraft_position') + +# +# Plot +# +fig = plt.figure() +axis1 = fig.add_subplot(111) +axis1.plot(time[0], solar_radiation_pressure_at_spacecraft_position_N_m2[0], marker=".", c="red", label="Pressure N/m2") +axis1.set_ylabel("Solar Radiation Pressure [N/m2]") +axis1.legend() + +axis2 = axis1.twinx() +axis2.plot(time[0], shadow_coefficient_at_spacecraft_position[0], marker=".", c="blue", label="Shadow Coefficient") +axis2.set_ylabel("Shadow Coefficient") +axis2.legend() +axis2.set_ylim(0, 2) + +plt.title("Solar radiation pressure environment") +plt.xlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_solar_radiation_environment.png") # save last figure only +else: + plt.show() From e9857c1841a20d7352cf924b87e63d09d379fb71 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:48:15 +0100 Subject: [PATCH 0971/1086] Add plot for air density --- scripts/Plot/plot_air_density.py | 65 ++++++++++++++++++++++++++++++++ 1 file changed, 65 insertions(+) create mode 100644 scripts/Plot/plot_air_density.py diff --git a/scripts/Plot/plot_air_density.py b/scripts/Plot/plot_air_density.py new file mode 100644 index 000000000..11a9d52c3 --- /dev/null +++ b/scripts/Plot/plot_air_density.py @@ -0,0 +1,65 @@ +# +# Plot air density at the spacecraft position +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +air_density_at_spacecraft_position_kg_m3 = read_scalar_from_csv(read_file_name, 'air_density_at_spacecraft_position[kg/m3]') + +# +# Plot +# +plt.figure(0) +plt.plot(time[0], air_density_at_spacecraft_position_kg_m3[0], marker=".", c="red") +plt.title("Air density at the spacecraft position") +plt.xlabel("Time [s]") +plt.ylabel("Air density [kg/m3]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_air_density.png") # save last figure only +else: + plt.show() From c511cbde2df39ecdf86d63c579a146bebc098b03 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:51:43 +0100 Subject: [PATCH 0972/1086] Remove unnecessary unit in log header --- src/environment/local/atmosphere.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index 0552fd4a2..f8d27d1d9 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -217,7 +217,7 @@ std::string Atmosphere::GetLogValue() const { std::string Atmosphere::GetLogHeader() const { std::string str_tmp = ""; - str_tmp += WriteScalar("air_density_kg_m3_at_spacecraft_position", "kg/m3"); + str_tmp += WriteScalar("air_density_at_spacecraft_position", "kg/m3"); return str_tmp; } From 6804414553050f78b490cf1fc59b5b744dd4ef30 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 19:57:05 +0100 Subject: [PATCH 0973/1086] Fix unit in plot --- scripts/Plot/plot_celestial_orbit_i.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/Plot/plot_celestial_orbit_i.py b/scripts/Plot/plot_celestial_orbit_i.py index a26bff25c..ac89a0cfc 100644 --- a/scripts/Plot/plot_celestial_orbit_i.py +++ b/scripts/Plot/plot_celestial_orbit_i.py @@ -71,7 +71,7 @@ plt.plot(time[0], sun_velocity_i_m_s[2], marker=".", c="blue", label="Z") plt.title("Sun Velocity @ the inertial frame") plt.xlabel("Time [s]") -plt.ylabel("Velocity [m]") +plt.ylabel("Velocity [m/s]") plt.legend() plt.figure(2) @@ -89,7 +89,7 @@ plt.plot(time[0], moon_velocity_i_m_s[2], marker=".", c="blue", label="Z") plt.title("Moon Velocity @ the inertial frame") plt.xlabel("Time [s]") -plt.ylabel("Velocity [m]") +plt.ylabel("Velocity [m/s]") plt.legend() From 168927beed1310eb1cde30e4855167d1786a0171 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 20:03:50 +0100 Subject: [PATCH 0974/1086] Fix x label --- scripts/Plot/plot_solar_radiation_environment.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/Plot/plot_solar_radiation_environment.py b/scripts/Plot/plot_solar_radiation_environment.py index 11b67b12a..3bc055972 100644 --- a/scripts/Plot/plot_solar_radiation_environment.py +++ b/scripts/Plot/plot_solar_radiation_environment.py @@ -66,7 +66,7 @@ axis2.set_ylim(0, 2) plt.title("Solar radiation pressure environment") -plt.xlabel("Time [s]") +axis1.set_xlabel("Time [s]") # Data save if args.no_gui: From bf8e5f2efb90ef0ea00e10c2613957c23aa74539 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 20:47:06 +0100 Subject: [PATCH 0975/1086] Add plot for gyro sensor --- scripts/Plot/plot_gyro_sensor.py | 81 ++++++++++++++++++++++++++++++++ 1 file changed, 81 insertions(+) create mode 100644 scripts/Plot/plot_gyro_sensor.py diff --git a/scripts/Plot/plot_gyro_sensor.py b/scripts/Plot/plot_gyro_sensor.py new file mode 100644 index 000000000..6dcf5df44 --- /dev/null +++ b/scripts/Plot/plot_gyro_sensor.py @@ -0,0 +1,81 @@ +# +# Plot Gyro Sensor +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +measured_angular_velocity_c_rad_s = read_3d_vector_from_csv(read_file_name, 'gyro_sensor1_measured_angular_velocity_c', 'rad/s') +true_angular_velocity_b_rad_s = read_3d_vector_from_csv(read_file_name, 'spacecraft_angular_velocity_b', 'rad/s') + +# +# Plot +# +plt.figure(0) + +plt.subplot(3, 1, 1) +plt.plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="GYRO-X") +plt.plot(time[0], true_angular_velocity_b_rad_s[0], marker=".", c="orange", label="TRUE-X") +plt.legend() + +plt.subplot(3, 1, 2) +plt.plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="GYRO-Y") +plt.plot(time[0], true_angular_velocity_b_rad_s[1], marker=".", c="yellow", label="TRUE-Y") +plt.ylabel("Angular Velocity [rad/s]") +plt.legend() + +plt.subplot(3, 1, 3) +plt.plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="GYRO-Z") +plt.plot(time[0], true_angular_velocity_b_rad_s[2], marker=".", c="purple", label="TRUE-Z") +plt.legend() +plt.xlabel("Time [s]") + +plt.suptitle("Gyro Sensor Angular Velocity") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_gyro_sensor.png") # save last figure only +else: + plt.show() From cf4ff8a625356bc849fdcfe484dcdca548d7daa8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 21:35:36 +0100 Subject: [PATCH 0976/1086] Add statistics --- scripts/Plot/plot_gyro_sensor.py | 45 ++++++++++++++++++++------------ 1 file changed, 28 insertions(+), 17 deletions(-) diff --git a/scripts/Plot/plot_gyro_sensor.py b/scripts/Plot/plot_gyro_sensor.py index 6dcf5df44..166e59307 100644 --- a/scripts/Plot/plot_gyro_sensor.py +++ b/scripts/Plot/plot_gyro_sensor.py @@ -50,29 +50,40 @@ measured_angular_velocity_c_rad_s = read_3d_vector_from_csv(read_file_name, 'gyro_sensor1_measured_angular_velocity_c', 'rad/s') true_angular_velocity_b_rad_s = read_3d_vector_from_csv(read_file_name, 'spacecraft_angular_velocity_b', 'rad/s') +# Statistics +# We assume that the component frame and the body frame is same +error_rad_s = measured_angular_velocity_c_rad_s - true_angular_velocity_b_rad_s +average = [0.0, 0.0, 0.0] +standard_deviation = [0.0, 0.0, 0.0] +for i in range(3): + average[i] = error_rad_s[i].mean() + standard_deviation[i] = error_rad_s[i].std() + # # Plot # -plt.figure(0) - -plt.subplot(3, 1, 1) -plt.plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="GYRO-X") -plt.plot(time[0], true_angular_velocity_b_rad_s[0], marker=".", c="orange", label="TRUE-X") -plt.legend() +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="GYRO-X") +axis[0, 0].plot(time[0], true_angular_velocity_b_rad_s[0], marker=".", c="orange", label="TRUE-X") +axis[0, 0].legend() +axis[0, 0].text(0.01, 0.99, "average:" + format(average[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) -plt.subplot(3, 1, 2) -plt.plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="GYRO-Y") -plt.plot(time[0], true_angular_velocity_b_rad_s[1], marker=".", c="yellow", label="TRUE-Y") -plt.ylabel("Angular Velocity [rad/s]") -plt.legend() +axis[1, 0].plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="GYRO-Y") +axis[1, 0].plot(time[0], true_angular_velocity_b_rad_s[1], marker=".", c="yellow", label="TRUE-Y") +axis[1, 0].legend() +axis[1, 0].text(0.01, 0.99, "average:" + format(average[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) -plt.subplot(3, 1, 3) -plt.plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="GYRO-Z") -plt.plot(time[0], true_angular_velocity_b_rad_s[2], marker=".", c="purple", label="TRUE-Z") -plt.legend() -plt.xlabel("Time [s]") +axis[2, 0].plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="GYRO-Z") +axis[2, 0].plot(time[0], true_angular_velocity_b_rad_s[2], marker=".", c="purple", label="TRUE-Z") +axis[2, 0].legend() +axis[2, 0].text(0.01, 0.99, "average:" + format(average[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) -plt.suptitle("Gyro Sensor Angular Velocity") +fig.suptitle("Gyro Sensor Angular Velocity") +fig.supylabel("Angular Velocity [rad/s]") +fig.supxlabel("Time [s]") # Data save if args.no_gui: From a31552549140b477579ac84e02e4960a78848090 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 22:07:58 +0100 Subject: [PATCH 0977/1086] Fix gyro sensor default noise --- .../initialize_files/components/gyro_sensor.ini | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/gyro_sensor.ini b/data/sample/initialize_files/components/gyro_sensor.ini index 32b0c51cb..84f8948a6 100644 --- a/data/sample/initialize_files/components/gyro_sensor.ini +++ b/data/sample/initialize_files/components/gyro_sensor.ini @@ -27,9 +27,9 @@ constant_bias_c_rad_s(1) = -1.0e-3 constant_bias_c_rad_s(2) = 2.0e-3 // Standard deviation for random walk noise[rad/s] -normal_random_standard_deviation_c_rad_s(0) = 0.0 -normal_random_standard_deviation_c_rad_s(1) = 0.0 -normal_random_standard_deviation_c_rad_s(2) = 0.0 +random_walk_standard_deviation_c_rad_s(0) = 0.0 +random_walk_standard_deviation_c_rad_s(1) = 0.0 +random_walk_standard_deviation_c_rad_s(2) = 0.0 // Limit of random walk noise[rad/s] random_walk_limit_c_rad_s(0) = 0.0 @@ -37,9 +37,9 @@ random_walk_limit_c_rad_s(1) = 0.0 random_walk_limit_c_rad_s(2) = 0.0 // Standard deviation of normal random noise[rad/s] -random_walk_standard_deviation_c_rad_s(0) = 1e-3 -random_walk_standard_deviation_c_rad_s(1) = 1e-3 -random_walk_standard_deviation_c_rad_s(2) = 1e-3 +normal_random_standard_deviation_c_rad_s(0) = 1e-3 +normal_random_standard_deviation_c_rad_s(1) = 1e-3 +normal_random_standard_deviation_c_rad_s(2) = 1e-3 // Range [rad/s] range_to_constant_rad_s = 5.0 // smaller than Range_to_zero From a52296cb17b5a064ea8b8c1ae5ba41e11d08701c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 22:34:21 +0100 Subject: [PATCH 0978/1086] git fix legend --- scripts/Plot/plot_gyro_sensor.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/scripts/Plot/plot_gyro_sensor.py b/scripts/Plot/plot_gyro_sensor.py index 166e59307..b6ae4c307 100644 --- a/scripts/Plot/plot_gyro_sensor.py +++ b/scripts/Plot/plot_gyro_sensor.py @@ -65,19 +65,19 @@ fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) axis[0, 0].plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="GYRO-X") axis[0, 0].plot(time[0], true_angular_velocity_b_rad_s[0], marker=".", c="orange", label="TRUE-X") -axis[0, 0].legend() +axis[0, 0].legend(loc = 'upper right') axis[0, 0].text(0.01, 0.99, "average:" + format(average[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) axis[0, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) axis[1, 0].plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="GYRO-Y") axis[1, 0].plot(time[0], true_angular_velocity_b_rad_s[1], marker=".", c="yellow", label="TRUE-Y") -axis[1, 0].legend() +axis[1, 0].legend(loc = 'upper right') axis[1, 0].text(0.01, 0.99, "average:" + format(average[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) axis[1, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) axis[2, 0].plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="GYRO-Z") axis[2, 0].plot(time[0], true_angular_velocity_b_rad_s[2], marker=".", c="purple", label="TRUE-Z") -axis[2, 0].legend() +axis[2, 0].legend(loc = 'upper right') axis[2, 0].text(0.01, 0.99, "average:" + format(average[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) axis[2, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) From 24d7c324502e9e6c7a402f65361d28dd22b23ac5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 22:44:42 +0100 Subject: [PATCH 0979/1086] Add plot for magnetometer --- scripts/Plot/plot_magnetometer.py | 92 +++++++++++++++++++++++++++++++ 1 file changed, 92 insertions(+) create mode 100644 scripts/Plot/plot_magnetometer.py diff --git a/scripts/Plot/plot_magnetometer.py b/scripts/Plot/plot_magnetometer.py new file mode 100644 index 000000000..b66691802 --- /dev/null +++ b/scripts/Plot/plot_magnetometer.py @@ -0,0 +1,92 @@ +# +# Plot Magnetometer +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +measured_magnetic_field_c_nT = read_3d_vector_from_csv(read_file_name, 'magnetometer1_measured_magnetic_field_c', 'nT') +true_magnetic_field_b_nT = read_3d_vector_from_csv(read_file_name, 'geomagnetic_field_at_spacecraft_position_b', 'nT') + +# Statistics +# We assume that the component frame and the body frame is same +error_rad_s = measured_magnetic_field_c_nT - true_magnetic_field_b_nT +average = [0.0, 0.0, 0.0] +standard_deviation = [0.0, 0.0, 0.0] +for i in range(3): + average[i] = error_rad_s[i].mean() + standard_deviation[i] = error_rad_s[i].std() + +# +# Plot +# +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], measured_magnetic_field_c_nT[0], marker=".", c="red", label="MEASURED-X") +axis[0, 0].plot(time[0], true_magnetic_field_b_nT[0], marker=".", c="orange", label="TRUE-X") +axis[0, 0].legend(loc = 'upper right') +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) + +axis[1, 0].plot(time[0], measured_magnetic_field_c_nT[1], marker=".", c="green", label="MEASURED-Y") +axis[1, 0].plot(time[0], true_magnetic_field_b_nT[1], marker=".", c="yellow", label="TRUE-Y") +axis[1, 0].legend(loc = 'upper right') +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) + +axis[2, 0].plot(time[0], measured_magnetic_field_c_nT[2], marker=".", c="blue", label="MEASURED-Z") +axis[2, 0].plot(time[0], true_magnetic_field_b_nT[2], marker=".", c="purple", label="TRUE-Z") +axis[2, 0].legend(loc = 'upper right') +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) + +fig.suptitle("Magnetometer Magnetic field") +fig.supylabel("Magnetic Field [nT]") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_magnetometer.png") # save last figure only +else: + plt.show() From f2adaf71869563d8011aa4088b94ee4ae9eeb179 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 22:56:35 +0100 Subject: [PATCH 0980/1086] Add unit information --- scripts/Plot/plot_gyro_sensor.py | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/scripts/Plot/plot_gyro_sensor.py b/scripts/Plot/plot_gyro_sensor.py index b6ae4c307..569e174dd 100644 --- a/scripts/Plot/plot_gyro_sensor.py +++ b/scripts/Plot/plot_gyro_sensor.py @@ -62,27 +62,29 @@ # # Plot # +unit = ' rad/s' + fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) -axis[0, 0].plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="GYRO-X") +axis[0, 0].plot(time[0], measured_angular_velocity_c_rad_s[0], marker=".", c="red", label="MEASURED-X") axis[0, 0].plot(time[0], true_angular_velocity_b_rad_s[0], marker=".", c="orange", label="TRUE-X") axis[0, 0].legend(loc = 'upper right') -axis[0, 0].text(0.01, 0.99, "average:" + format(average[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) -axis[0, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) -axis[1, 0].plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="GYRO-Y") +axis[1, 0].plot(time[0], measured_angular_velocity_c_rad_s[1], marker=".", c="green", label="MEASURED-Y") axis[1, 0].plot(time[0], true_angular_velocity_b_rad_s[1], marker=".", c="yellow", label="TRUE-Y") axis[1, 0].legend(loc = 'upper right') -axis[1, 0].text(0.01, 0.99, "average:" + format(average[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) -axis[1, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) -axis[2, 0].plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="GYRO-Z") +axis[2, 0].plot(time[0], measured_angular_velocity_c_rad_s[2], marker=".", c="blue", label="MEASURED-Z") axis[2, 0].plot(time[0], true_angular_velocity_b_rad_s[2], marker=".", c="purple", label="TRUE-Z") axis[2, 0].legend(loc = 'upper right') -axis[2, 0].text(0.01, 0.99, "average:" + format(average[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) -axis[2, 0].text(0.01, 0.89, "standard deviation:" + format(standard_deviation[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) fig.suptitle("Gyro Sensor Angular Velocity") -fig.supylabel("Angular Velocity [rad/s]") +fig.supylabel("Angular Velocity" + unit) fig.supxlabel("Time [s]") # Data save From 62c89f1624f102ac9e21d811a6275ffd6398868e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 1 Mar 2023 22:58:12 +0100 Subject: [PATCH 0981/1086] Add unit information --- scripts/Plot/plot_magnetometer.py | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/scripts/Plot/plot_magnetometer.py b/scripts/Plot/plot_magnetometer.py index b66691802..afb737fd2 100644 --- a/scripts/Plot/plot_magnetometer.py +++ b/scripts/Plot/plot_magnetometer.py @@ -62,27 +62,29 @@ # # Plot # +unit = ' nT' + fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) axis[0, 0].plot(time[0], measured_magnetic_field_c_nT[0], marker=".", c="red", label="MEASURED-X") axis[0, 0].plot(time[0], true_magnetic_field_b_nT[0], marker=".", c="orange", label="TRUE-X") axis[0, 0].legend(loc = 'upper right') -axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) -axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e'), verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) axis[1, 0].plot(time[0], measured_magnetic_field_c_nT[1], marker=".", c="green", label="MEASURED-Y") axis[1, 0].plot(time[0], true_magnetic_field_b_nT[1], marker=".", c="yellow", label="TRUE-Y") axis[1, 0].legend(loc = 'upper right') -axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) -axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e'), verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) axis[2, 0].plot(time[0], measured_magnetic_field_c_nT[2], marker=".", c="blue", label="MEASURED-Z") axis[2, 0].plot(time[0], true_magnetic_field_b_nT[2], marker=".", c="purple", label="TRUE-Z") axis[2, 0].legend(loc = 'upper right') -axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) -axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e'), verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) fig.suptitle("Magnetometer Magnetic field") -fig.supylabel("Magnetic Field [nT]") +fig.supylabel("Magnetic Field" + unit) fig.supxlabel("Time [s]") # Data save From fa096c1661eb76dc4c72117c8b02885bbf8b920c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 09:24:33 +0100 Subject: [PATCH 0982/1086] Add quaternion read function --- scripts/Plot/common.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/scripts/Plot/common.py b/scripts/Plot/common.py index ff373e5fd..6ffbc4483 100644 --- a/scripts/Plot/common.py +++ b/scripts/Plot/common.py @@ -34,6 +34,18 @@ def read_3d_vector_from_csv(read_file_name, header_name, unit): csv_data[name_z].to_numpy()]) return vector +def read_quaternion_from_csv(read_file_name, header_name): + name_x = header_name + "_x" + name_y = header_name + "_y" + name_z = header_name + "_z" + name_w = header_name + "_w" + csv_data = pandas.read_csv(read_file_name, sep=',', usecols=[name_x, name_y, name_z, name_w]) + quaternion = np.array([csv_data[name_x].to_numpy(), + csv_data[name_y].to_numpy(), + csv_data[name_z].to_numpy(), + csv_data[name_w].to_numpy()]) + return quaternion + def read_scalar_from_csv(read_file_name, header_name): csv_data = pandas.read_csv(read_file_name, sep=',', usecols=[header_name]) vector = np.array([csv_data[header_name].to_numpy()]) From e14361b5446ba44927e229f29c17311f4267998e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 09:24:52 +0100 Subject: [PATCH 0983/1086] Add plot for star sensor --- scripts/Plot/plot_star_sensor.py | 82 ++++++++++++++++++++++++++++++++ 1 file changed, 82 insertions(+) create mode 100644 scripts/Plot/plot_star_sensor.py diff --git a/scripts/Plot/plot_star_sensor.py b/scripts/Plot/plot_star_sensor.py new file mode 100644 index 000000000..382f15e6b --- /dev/null +++ b/scripts/Plot/plot_star_sensor.py @@ -0,0 +1,82 @@ +# +# Plot Star Sensor +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_quaternion_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +measured_quaternion_i2c = read_quaternion_from_csv(read_file_name, 'stt1_measured_quaternion_i2c') +true_quaternion_i2b = read_quaternion_from_csv(read_file_name, 'spacecraft_quaternion_i2b') + +# +# Plot +# + +fig, axis = plt.subplots(4, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], measured_quaternion_i2c[0], marker=".", c="red", label="MEASURED-X") +axis[0, 0].plot(time[0], true_quaternion_i2b[0], marker=".", c="orange", label="TRUE-X") +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], measured_quaternion_i2c[1], marker=".", c="green", label="MEASURED-Y") +axis[1, 0].plot(time[0], true_quaternion_i2b[1], marker=".", c="yellow", label="TRUE-Y") +axis[1, 0].legend(loc = 'upper right') + +axis[2, 0].plot(time[0], measured_quaternion_i2c[2], marker=".", c="blue", label="MEASURED-Z") +axis[2, 0].plot(time[0], true_quaternion_i2b[2], marker=".", c="purple", label="TRUE-Z") +axis[2, 0].legend(loc = 'upper right') + +axis[3, 0].plot(time[0], measured_quaternion_i2c[3], marker=".", c="black", label="MEASURED-W") +axis[3, 0].plot(time[0], true_quaternion_i2b[3], marker=".", c="gray", label="TRUE-W") +axis[3, 0].legend(loc = 'upper right') + +fig.suptitle("Star Sensor Quaternion") +fig.supylabel("Quaternion") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_star_sensor.png") # save last figure only +else: + plt.show() From 5d8e607acf2fb0f2dfc7477b4f5b747eb6a1fb61 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 09:31:41 +0100 Subject: [PATCH 0984/1086] Add numpy-quaternion --- scripts/Plot/Pipfile | 1 + scripts/Plot/Pipfile.lock | 49 +++++++++++++++++++++++++++++++- scripts/Plot/plot_star_sensor.py | 3 ++ 3 files changed, 52 insertions(+), 1 deletion(-) diff --git a/scripts/Plot/Pipfile b/scripts/Plot/Pipfile index 338b48c66..027491c3c 100644 --- a/scripts/Plot/Pipfile +++ b/scripts/Plot/Pipfile @@ -9,6 +9,7 @@ matplotlib = "==3.6.3" numpy = "==1.23.5" pandas = "==1.5.3" numpy-stl = "==3.0.0" +numpy-quaternion = "*" [dev-packages] diff --git a/scripts/Plot/Pipfile.lock b/scripts/Plot/Pipfile.lock index 422476ce5..065b10e69 100644 --- a/scripts/Plot/Pipfile.lock +++ b/scripts/Plot/Pipfile.lock @@ -1,7 +1,7 @@ { "_meta": { "hash": { - "sha256": "f8f8f0802c1f1c0284a258345b59a5d36c0fbdf2df4bd2d8d48a425a0b07a423" + "sha256": "4bbc224d0f4e557cade242dd06064911bdc580475825ea6c9f007f2beaa43d04" }, "pipfile-spec": 6, "requires": { @@ -303,6 +303,53 @@ "index": "pypi", "version": "==1.23.5" }, + "numpy-quaternion": { + "hashes": [ + "sha256:0fc5aed22a2170eb2c65aa3a0d10c08883ec9fdc35d10c110d38811f736d609a", + "sha256:158df059771f5c2baa2fa43f166be30c0507aacea7df1c6fd67eb4c404b3fae3", + "sha256:1a82205a785be37c1a2ae28dd13c02a6aaf43e7a1f3ac4cb57f6efc2d2e5d8a1", + "sha256:1ebd03fb341ae3f837d6d9d96df25b1c4bc0dafd9ffcb562eebdae29496f175e", + "sha256:2ebb925346ee4a7c1ac3d9d00383950ad610d7cc672445b7b7f67e0a3a03df40", + "sha256:334376b88dcede4263f1338b4ab40e1124c7a8fc8f81e3c3e1070cc0f5da10a7", + "sha256:364c142af3ba8aac3ee6de9ab652a409133d23d81642c18fae150585b006cf85", + "sha256:3c7de12e8270e6b4fa7da9da372134a56a85eebbb1b1d81e8419e8315cea7227", + "sha256:4605a23c57fead0c20623e55b473fa233b082b5ed4d83553da6c2cb83541f428", + "sha256:4b685200964fd9e654c12cc298d5d086ef0a0313ee2b17d6b9ff29a3a880d803", + "sha256:4f07823341642943d24cddc10f07cb4e32e10f5cc033fb42aa2f181e8bf0699f", + "sha256:53bcaa3c0fb245623a092eb43224e30b883882b3460143487cccf9797fc865ae", + "sha256:556c32f082bb97aab9f41f7154b4d7f004a22c3187f056e78d17bf818644804f", + "sha256:5d9e6bec15afeba28022b7a44fdf28da27fd0422075b76be99c5be70969d52e6", + "sha256:71a5f6fbf64001369f178168a46287dce33157947272073258d20e846b0f40a4", + "sha256:75c734f4b3f887f465da3571afeff924781f53dbf39c8da199fb860b9f4dc3ec", + "sha256:7cfec847bca62ff2ff50b190fb0e7c733a0f7f42ce6ac6385166bf6c814d5b15", + "sha256:7d97d22a082caa924f2ebd998563437884e1f578c5cdb8ba001abc60d2909922", + "sha256:7e7c36d949d09e07bd091bae1cb7c56b7dcedfb2c570f89e75be6de9f37d44a6", + "sha256:8761f80fc4f510147bf690d494668f0944a2d590e2c5ada9d7c62af6a46e81ad", + "sha256:8d635131afbd49dafa9463c78bf1a298c9de35cc759e6008647c714780e68de7", + "sha256:9a7fcf818691aec1250f53c99c7958f57e09489e5ce1371b3a5342b65439da9d", + "sha256:9b17ebddb0bd3fe646fc56b0e8693a92561e704be541bc3dcb4282988ebb01ed", + "sha256:9ebf377c7174f4b32e1078e4607afbb3c4e0d0365dc633d43654f01e3703e800", + "sha256:a0aaa74a13799e13bb9b6a65964401260f7a5482d2f7e50f5e564c8866f8b96f", + "sha256:a3b4ed4ca225c7f5965ddc18a8cba0f7ea8406a869872d18d1f9900420ebdd38", + "sha256:a4db146a130d53cea5d74543950e5ebd01dd7603dfe5a42d4f3ebc76539551bb", + "sha256:accbe7758561a4bb3bd486b5f754b9983bc1be17ee517feb715d7e363833407f", + "sha256:c403eeddfc19cb3b400abbd6daabd9aec9843344e9b9c739f080d27291e3d75e", + "sha256:c521e6ee255c74f1ef604bd8ebdfdc32225d9ac7ce52c731562d4b4e01358793", + "sha256:c5f13b7faa8b9859fba94f1425d9ac6478d74fa2b26f5cb0b8258a48365ee49b", + "sha256:ca29e8f961673932d123a8b2520ef7ded9fee4e426aed628d90ced0749608285", + "sha256:ca37256f544a7e587ab08c1841a30e34aa7b85c7c9663527c61d77fbcad9dda7", + "sha256:ca743f7ca7a86b555cfc7e9f72acb7eb50fd56ec28834432b54b00896ba6363a", + "sha256:ccf9b0fc0e6b2a1f6c5a0bf2e5affbc588cc09d5ba585d176bd92e9f4bdfd7a1", + "sha256:ce50c414e884d8d18615cb6b5c928929e9dcff2f98f4606b2cc7a5b4dd5f5fb4", + "sha256:d35e7bdc02025601d21830c6419e1317059083e1a3ccab68df5113b167e3fc61", + "sha256:ded4c4122481b465e46374d9087da280d712d7ea500b34fc03ae854cfc3c86b5", + "sha256:e34ed9c325dcd631b67dcf30b6f493528228622bc8b8b9abfaf68166fc367151", + "sha256:e4b28a372b1362b75a23d3abf08fcc5a77c950aa554136137c5f2cd5d3a45edb", + "sha256:f9a7ed1ee9954e06e81847600eefa11d162e9cbbd386a0c693f0f681ec731133" + ], + "index": "pypi", + "version": "==2022.4.3" + }, "numpy-stl": { "hashes": [ "sha256:44d56dec3b409b73f7126089ece859d0213d302e39c2375496e64f6dc574347c", diff --git a/scripts/Plot/plot_star_sensor.py b/scripts/Plot/plot_star_sensor.py index 382f15e6b..e27b1bb47 100644 --- a/scripts/Plot/plot_star_sensor.py +++ b/scripts/Plot/plot_star_sensor.py @@ -9,6 +9,9 @@ # # plots import matplotlib.pyplot as plt +# quaternion +import numpy as np +import quaternion # local function from common import find_latest_log_tag from common import add_log_file_arguments From be9249a479084b817b79921850994bf8bc00f9b6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 11:10:40 +0100 Subject: [PATCH 0985/1086] Add error angle plot --- scripts/Plot/common.py | 12 ++++++++++++ scripts/Plot/plot_star_sensor.py | 16 +++++++++++++--- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/scripts/Plot/common.py b/scripts/Plot/common.py index 6ffbc4483..d53e6a8a3 100644 --- a/scripts/Plot/common.py +++ b/scripts/Plot/common.py @@ -1,6 +1,7 @@ import os import numpy as np from numpy.linalg import norm +import quaternion import pandas import argparse @@ -62,3 +63,14 @@ def add_stl_model(plot_axis, file_name, alpha=0.7, color='orange'): scale = 0.7 / sc_size_max plot_axis.add_collection3d(mpl_toolkits.mplot3d.art3d.Poly3DCollection(sc_mesh.vectors * scale, alpha=alpha, color=color)) +def calc_error_angle_from_quaternions(q1, q2): + # definition of input quaternion is (x, y, z, w) + np_q1 = quaternion.as_quat_array(np.transpose(q1[[3, 0, 1, 2], :])) + np_q2 = quaternion.as_quat_array(np.transpose(q2[[3, 0, 1, 2], :])) + error_np_quaternion = np_q2 * np_q1.conjugate() + + error_angle_rad = np.zeros(shape=(len(error_np_quaternion), 1)) + for i in range(len(error_np_quaternion)): + error_angle_rad[i] = error_np_quaternion[i].angle() # FIXME: error_np_quaternion.angle() didn't work... + + return error_angle_rad diff --git a/scripts/Plot/plot_star_sensor.py b/scripts/Plot/plot_star_sensor.py index e27b1bb47..26b402200 100644 --- a/scripts/Plot/plot_star_sensor.py +++ b/scripts/Plot/plot_star_sensor.py @@ -9,14 +9,12 @@ # # plots import matplotlib.pyplot as plt -# quaternion -import numpy as np -import quaternion # local function from common import find_latest_log_tag from common import add_log_file_arguments from common import read_quaternion_from_csv from common import read_scalar_from_csv +from common import calc_error_angle_from_quaternions # arguments import argparse @@ -53,6 +51,11 @@ measured_quaternion_i2c = read_quaternion_from_csv(read_file_name, 'stt1_measured_quaternion_i2c') true_quaternion_i2b = read_quaternion_from_csv(read_file_name, 'spacecraft_quaternion_i2b') +# Statistics +error_angle_rad = calc_error_angle_from_quaternions(measured_quaternion_i2c, true_quaternion_i2b) +error_average = error_angle_rad.mean() +standard_deviation = error_angle_rad.std() + # # Plot # @@ -78,6 +81,13 @@ fig.supylabel("Quaternion") fig.supxlabel("Time [s]") +unit = 'rad' +plt.figure(0) +plt.plot(time[0], error_angle_rad, marker=".", c="red") +plt.title("Error angle \n" + "Error average:" + format(error_average, '+.2e') + unit + "\n Standard deviation:" + format(standard_deviation, '+.2e') + unit) +plt.xlabel("Time [s]") +plt.ylabel("Angle [rad]") + # Data save if args.no_gui: plt.savefig(read_file_tag + "_star_sensor.png") # save last figure only From 78baffdcc14259bbf86185b3229259329a73fe76 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 11:30:25 +0100 Subject: [PATCH 0986/1086] Add plot sun sensor --- scripts/Plot/plot_sun_sensor | 86 ++++++++++++++++++++++++++++++++++++ 1 file changed, 86 insertions(+) create mode 100644 scripts/Plot/plot_sun_sensor diff --git a/scripts/Plot/plot_sun_sensor b/scripts/Plot/plot_sun_sensor new file mode 100644 index 000000000..842c6f7d2 --- /dev/null +++ b/scripts/Plot/plot_sun_sensor @@ -0,0 +1,86 @@ +# +# Plot Sun Sensor +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# numpy +import numpy as np +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +from common import normalize_csv_read_vector +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +measured_sun_direction_c = read_3d_vector_from_csv(read_file_name, 'sun_sensor1_measured_sun_direction_c', '-') +true_sun_direction_b = np.transpose(normalize_csv_read_vector(read_3d_vector_from_csv(read_file_name, 'sun_position_from_spacecraft_b', 'm'))) + +sun_detection_flag = read_scalar_from_csv(read_file_name, 'sun_sensor1_sun_detected_flag[-]') + +# +# Plot +# +fig, axis = plt.subplots(4, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], measured_sun_direction_c[0], marker=".", c="red", label="MEASURED-X") +axis[0, 0].plot(time[0], true_sun_direction_b[0], marker=".", c="orange", label="TRUE-X") +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], measured_sun_direction_c[1], marker=".", c="green", label="MEASURED-Y") +axis[1, 0].plot(time[0], true_sun_direction_b[1], marker=".", c="yellow", label="TRUE-Y") +axis[1, 0].legend(loc = 'upper right') + +axis[2, 0].plot(time[0], measured_sun_direction_c[2], marker=".", c="blue", label="MEASURED-Z") +axis[2, 0].plot(time[0], true_sun_direction_b[2], marker=".", c="purple", label="TRUE-Z") +axis[2, 0].legend(loc = 'upper right') + +axis[3, 0].plot(time[0], sun_detection_flag[0], marker=".", c="black", label="SUN-FLAG") +axis[3, 0].legend(loc = 'upper right') +axis[3, 0].set_ylim(0, 1.2) + +fig.suptitle("Sun Sensor Sun direction at the body frame") +fig.supylabel("Sun direction") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_sun_sensor.png") # save last figure only +else: + plt.show() From 316709f74bfd8fccd566548711a2e085342e2797 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 13:21:46 +0100 Subject: [PATCH 0987/1086] Add plot for gnss receiver --- scripts/Plot/plot_gnss_receiver.py | 105 +++++++++++++++++++++++++++++ 1 file changed, 105 insertions(+) create mode 100644 scripts/Plot/plot_gnss_receiver.py diff --git a/scripts/Plot/plot_gnss_receiver.py b/scripts/Plot/plot_gnss_receiver.py new file mode 100644 index 000000000..d650c18b3 --- /dev/null +++ b/scripts/Plot/plot_gnss_receiver.py @@ -0,0 +1,105 @@ +# +# Plot GNSS Receiver TODO: Add plot for velocity, time, geodetic position? +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# numpy +import numpy as np +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +measured_position_eci_m = read_3d_vector_from_csv(read_file_name, 'gnss_receiver1_measured_position_eci', 'm') +true_position_eci_m = read_3d_vector_from_csv(read_file_name, 'spacecraft_position_i', 'm') + +number_of_visible_satellites = read_scalar_from_csv(read_file_name, 'gnss_receiver1_number_of_visible_satellites') +satellite_visible_flag = read_scalar_from_csv(read_file_name, 'gnss_receiver1_satellite_visible_flag') + +# Statistics +error_m = measured_position_eci_m[:, 1:] - true_position_eci_m[:, 1:] +average = [0.0, 0.0, 0.0] +standard_deviation = [0.0, 0.0, 0.0] +for i in range(3): + average[i] = error_m[i].mean() + standard_deviation[i] = error_m[i].std() + +# +# Plot +# +unit = ' m' +fig, axis = plt.subplots(5, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], measured_position_eci_m[0], marker=".", c="red", label="MEASURED-X") +axis[0, 0].plot(time[0], true_position_eci_m[0], marker=".", c="orange", label="TRUE-X") +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.79, "Standard deviation:" + format(standard_deviation[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], measured_position_eci_m[1], marker=".", c="green", label="MEASURED-Y") +axis[1, 0].plot(time[0], true_position_eci_m[1], marker=".", c="yellow", label="TRUE-Y") +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.79, "Standard deviation:" + format(standard_deviation[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].legend(loc = 'upper right') + +axis[2, 0].plot(time[0], measured_position_eci_m[2], marker=".", c="blue", label="MEASURED-Z") +axis[2, 0].plot(time[0], true_position_eci_m[2], marker=".", c="purple", label="TRUE-Z") +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.79, "Standard deviation:" + format(standard_deviation[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].legend(loc = 'upper right') + +axis[3, 0].plot(time[0], satellite_visible_flag[0], marker=".", c="black", label="VISIBLE-FLAG") +axis[3, 0].legend(loc = 'upper right') +axis[3, 0].set_ylim(0, 1.2) + +axis[4, 0].plot(time[0], number_of_visible_satellites[0], marker=".", c="black", label="VISIBLE-SATELLITE-NUMBER") +axis[4, 0].legend(loc = 'upper right') +axis[4, 0].set_ylim(0, max(number_of_visible_satellites[0]) + 2) + +fig.suptitle("GNSS Receiver Spacecraft position @ ECI") +fig.supylabel("Position [m]") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_gnss_receiver.png") # save last figure only +else: + plt.show() From c3325359645c4866d287806916a7a3ca450a1324 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 13:40:32 +0100 Subject: [PATCH 0988/1086] Add plot for magnetorquer --- scripts/Plot/plot_magnetorquer.py | 79 +++++++++++++++++++++++++++++++ 1 file changed, 79 insertions(+) create mode 100644 scripts/Plot/plot_magnetorquer.py diff --git a/scripts/Plot/plot_magnetorquer.py b/scripts/Plot/plot_magnetorquer.py new file mode 100644 index 000000000..972e83d80 --- /dev/null +++ b/scripts/Plot/plot_magnetorquer.py @@ -0,0 +1,79 @@ +# +# Plot Magnetorquer +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# numpy +import numpy as np +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +output_magnetic_moment_b_Am2 = read_3d_vector_from_csv(read_file_name, 'magnetorquer1_output_magnetic_moment_b', 'Am2') +output_torque_b_Nm = read_3d_vector_from_csv(read_file_name, 'magnetorquer1_output_torque_b', 'Nm') + +# +# Plot +# +unit = ' m' +fig, axis = plt.subplots(2, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], output_magnetic_moment_b_Am2[0], marker=".", c="red", label="X") +axis[0, 0].plot(time[0], output_magnetic_moment_b_Am2[1], marker=".", c="green", label="Y") +axis[0, 0].plot(time[0], output_magnetic_moment_b_Am2[2], marker=".", c="blue", label="Z") +axis[0, 0].set(ylabel = "Magnetic Moment Am2") +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], output_torque_b_Nm[0], marker=".", c="red", label="X") +axis[1, 0].plot(time[0], output_torque_b_Nm[1], marker=".", c="green", label="Y") +axis[1, 0].plot(time[0], output_torque_b_Nm[2], marker=".", c="blue", label="Z") +axis[1, 0].set(ylabel = "Torque Nm") +axis[1, 0].legend(loc = 'upper right') + +fig.suptitle("Magnetorquer Output @ Body frame") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_magnetorquer.png") # save last figure only +else: + plt.show() From 9509e781708f38bfdbc3f6dafc9a9fb995c2345b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 13:59:08 +0100 Subject: [PATCH 0989/1086] Add plot for RW --- scripts/Plot/plot_reaction_wheel.py | 78 +++++++++++++++++++++++++++++ 1 file changed, 78 insertions(+) create mode 100644 scripts/Plot/plot_reaction_wheel.py diff --git a/scripts/Plot/plot_reaction_wheel.py b/scripts/Plot/plot_reaction_wheel.py new file mode 100644 index 000000000..9e613bf5c --- /dev/null +++ b/scripts/Plot/plot_reaction_wheel.py @@ -0,0 +1,78 @@ +# +# Plot Magnetorquer +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# numpy +import numpy as np +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +angular_velocity_rad_s = read_scalar_from_csv(read_file_name, 'rw1_angular_velocity[rad/s]') +angular_velocity_rpm = read_scalar_from_csv(read_file_name, 'rw1_angular_velocity[rpm]') +angular_acceleration_rad_s2 = read_scalar_from_csv(read_file_name, 'rw1_angular_acceleration[rad/s2]') + +# +# Plot +# +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], angular_velocity_rad_s[0], marker=".", c="red", label="rad/s") +axis[0, 0].set(ylabel = "Angular velocity rad/s") +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], angular_velocity_rpm[0], marker=".", c="green", label="rpm") +axis[1, 0].set(ylabel = "Angular velocity rpm") +axis[1, 0].legend(loc = 'upper right') + +axis[2, 0].plot(time[0], angular_acceleration_rad_s2[0], marker=".", c="blue", label="rad/s2") +axis[2, 0].set(ylabel = "Angular acceleration rad/s2") +axis[2, 0].legend(loc = 'upper right') + +fig.suptitle("Reaction Wheel Output") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_reaction_wheel.png") # save last figure only +else: + plt.show() From ca026ca318541366c0bbfcbd216cb08dc9f454b2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 14:23:00 +0100 Subject: [PATCH 0990/1086] Delete unused variable --- scripts/Plot/plot_magnetorquer.py | 1 - 1 file changed, 1 deletion(-) diff --git a/scripts/Plot/plot_magnetorquer.py b/scripts/Plot/plot_magnetorquer.py index 972e83d80..413f5ab52 100644 --- a/scripts/Plot/plot_magnetorquer.py +++ b/scripts/Plot/plot_magnetorquer.py @@ -55,7 +55,6 @@ # # Plot # -unit = ' m' fig, axis = plt.subplots(2, 1, squeeze = False, tight_layout = True, sharex = True) axis[0, 0].plot(time[0], output_magnetic_moment_b_Am2[0], marker=".", c="red", label="X") axis[0, 0].plot(time[0], output_magnetic_moment_b_Am2[1], marker=".", c="green", label="Y") From ea50101ce1d747165bfbcaac4ad139615c0377bf Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 14:34:37 +0100 Subject: [PATCH 0991/1086] Add plot for simple thruster --- scripts/Plot/plot_simple_thruster.py | 78 ++++++++++++++++++++++++++++ 1 file changed, 78 insertions(+) create mode 100644 scripts/Plot/plot_simple_thruster.py diff --git a/scripts/Plot/plot_simple_thruster.py b/scripts/Plot/plot_simple_thruster.py new file mode 100644 index 000000000..c27494974 --- /dev/null +++ b/scripts/Plot/plot_simple_thruster.py @@ -0,0 +1,78 @@ +# +# Plot Simple Thruster +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# numpy +import numpy as np +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +output_thrust_b_N = read_3d_vector_from_csv(read_file_name, 'simple_thruster1_output_thrust_b', 'N') +output_torque_b_Nm = read_3d_vector_from_csv(read_file_name, 'simple_thruster1_output_torque_b', 'Nm') + +# +# Plot +# +fig, axis = plt.subplots(2, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], output_thrust_b_N[0], marker=".", c="red", label="X") +axis[0, 0].plot(time[0], output_thrust_b_N[1], marker=".", c="green", label="Y") +axis[0, 0].plot(time[0], output_thrust_b_N[2], marker=".", c="blue", label="Z") +axis[0, 0].set(ylabel = "Force N") +axis[0, 0].legend(loc = 'upper right') + +axis[1, 0].plot(time[0], output_torque_b_Nm[0], marker=".", c="red", label="X") +axis[1, 0].plot(time[0], output_torque_b_Nm[1], marker=".", c="green", label="Y") +axis[1, 0].plot(time[0], output_torque_b_Nm[2], marker=".", c="blue", label="Z") +axis[1, 0].set(ylabel = "Torque Nm") +axis[1, 0].legend(loc = 'upper right') + +fig.suptitle("Simple Thruster Output @ Body frame") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_simple_thruster.png") # save last figure only +else: + plt.show() From e2b37866085eea022fc82922beea6c88f4cb442e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 14:53:40 +0100 Subject: [PATCH 0992/1086] Add plot for force generator --- scripts/Plot/plot_force_generator.py | 94 ++++++++++++++++++++++++++++ 1 file changed, 94 insertions(+) create mode 100644 scripts/Plot/plot_force_generator.py diff --git a/scripts/Plot/plot_force_generator.py b/scripts/Plot/plot_force_generator.py new file mode 100644 index 000000000..06ea0134a --- /dev/null +++ b/scripts/Plot/plot_force_generator.py @@ -0,0 +1,94 @@ +# +# Plot Force Generator +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +ordered_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_ordered_force_b', 'N') +generated_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_generated_force_b', 'N') + +# Statistics +# We assume that the component frame and the body frame is same +error_rad_s = generated_force_b_N - ordered_force_b_N +average = [0.0, 0.0, 0.0] +standard_deviation = [0.0, 0.0, 0.0] +for i in range(3): + average[i] = error_rad_s[i].mean() + standard_deviation[i] = error_rad_s[i].std() + +# +# Plot +# +unit = ' N' + +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], ordered_force_b_N[0], marker=".", c="red", label="ORDERED-X") +axis[0, 0].plot(time[0], generated_force_b_N[0], marker=".", c="orange", label="GENERATED-X") +axis[0, 0].legend(loc = 'upper right') +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) + +axis[1, 0].plot(time[0], ordered_force_b_N[1], marker=".", c="green", label="ORDERED-Y") +axis[1, 0].plot(time[0], generated_force_b_N[1], marker=".", c="yellow", label="GENERATED-Y") +axis[1, 0].legend(loc = 'upper right') +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) + +axis[2, 0].plot(time[0], ordered_force_b_N[2], marker=".", c="blue", label="ORDERED-Z") +axis[2, 0].plot(time[0], generated_force_b_N[2], marker=".", c="purple", label="GENERATED-Z") +axis[2, 0].legend(loc = 'upper right') +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) + +fig.suptitle("Force Generator Output @ Body frame") +fig.supylabel("Force" + unit) +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_force_generator.png") # save last figure only +else: + plt.show() From 0256843305b56060d29b52a109402bd66a62edd5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 15:01:42 +0100 Subject: [PATCH 0993/1086] Add ECI and RTN frame plot --- scripts/Plot/plot_force_generator.py | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/scripts/Plot/plot_force_generator.py b/scripts/Plot/plot_force_generator.py index 06ea0134a..4ef79e0c5 100644 --- a/scripts/Plot/plot_force_generator.py +++ b/scripts/Plot/plot_force_generator.py @@ -49,6 +49,8 @@ ordered_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_ordered_force_b', 'N') generated_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_generated_force_b', 'N') +generated_force_i_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_generated_force_i', 'N') +generated_force_rtn_N = read_3d_vector_from_csv(read_file_name, 'ideal_force_generator_generated_force_rtn', 'N') # Statistics # We assume that the component frame and the body frame is same @@ -62,6 +64,25 @@ # # Plot # + +plt.figure(0) +plt.plot(time[0], generated_force_i_N[0], marker=".", c="red", label="X") +plt.plot(time[0], generated_force_i_N[1], marker=".", c="green", label="Y") +plt.plot(time[0], generated_force_i_N[2], marker=".", c="blue", label="Z") +plt.title("Generated Force @ Inertial frame") +plt.xlabel("Time [s]") +plt.ylabel("Force [N]") +plt.legend() + +plt.figure(1) +plt.plot(time[0], generated_force_rtn_N[0], marker=".", c="red", label="X") +plt.plot(time[0], generated_force_rtn_N[1], marker=".", c="green", label="Y") +plt.plot(time[0], generated_force_rtn_N[2], marker=".", c="blue", label="Z") +plt.title("Generated Force @ RTN frame") +plt.xlabel("Time [s]") +plt.ylabel("Force [N]") +plt.legend() + unit = ' N' fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) From 6f08b264f5ca35b567c5e5e387ac2e71581e624b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 15:05:26 +0100 Subject: [PATCH 0994/1086] Fix graph title --- scripts/Plot/plot_force_generator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/Plot/plot_force_generator.py b/scripts/Plot/plot_force_generator.py index 4ef79e0c5..2d6ab27f6 100644 --- a/scripts/Plot/plot_force_generator.py +++ b/scripts/Plot/plot_force_generator.py @@ -69,7 +69,7 @@ plt.plot(time[0], generated_force_i_N[0], marker=".", c="red", label="X") plt.plot(time[0], generated_force_i_N[1], marker=".", c="green", label="Y") plt.plot(time[0], generated_force_i_N[2], marker=".", c="blue", label="Z") -plt.title("Generated Force @ Inertial frame") +plt.title("Force Generator Generated Force @ Inertial frame") plt.xlabel("Time [s]") plt.ylabel("Force [N]") plt.legend() @@ -78,7 +78,7 @@ plt.plot(time[0], generated_force_rtn_N[0], marker=".", c="red", label="X") plt.plot(time[0], generated_force_rtn_N[1], marker=".", c="green", label="Y") plt.plot(time[0], generated_force_rtn_N[2], marker=".", c="blue", label="Z") -plt.title("Generated Force @ RTN frame") +plt.title("Force Generator Generated Force @ RTN frame") plt.xlabel("Time [s]") plt.ylabel("Force [N]") plt.legend() From 05d1801329dbbb2fbf312b9b6ef7979372a535ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 15:09:28 +0100 Subject: [PATCH 0995/1086] Add plot fot torque generator --- scripts/Plot/plot_torque_generator.py | 94 +++++++++++++++++++++++++++ 1 file changed, 94 insertions(+) create mode 100644 scripts/Plot/plot_torque_generator.py diff --git a/scripts/Plot/plot_torque_generator.py b/scripts/Plot/plot_torque_generator.py new file mode 100644 index 000000000..fb114be93 --- /dev/null +++ b/scripts/Plot/plot_torque_generator.py @@ -0,0 +1,94 @@ +# +# Plot Torque Generator +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_3d_vector_from_csv +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') + +ordered_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_torque_generator_ordered_torque_b', 'Nm') +generated_force_b_N = read_3d_vector_from_csv(read_file_name, 'ideal_torque_generator_generated_torque_b', 'Nm') + +# Statistics +# We assume that the component frame and the body frame is same +error_rad_s = generated_force_b_N - ordered_force_b_N +average = [0.0, 0.0, 0.0] +standard_deviation = [0.0, 0.0, 0.0] +for i in range(3): + average[i] = error_rad_s[i].mean() + standard_deviation[i] = error_rad_s[i].std() + +# +# Plot +# +unit = ' Nm' + +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], ordered_force_b_N[0], marker=".", c="red", label="ORDERED-X") +axis[0, 0].plot(time[0], generated_force_b_N[0], marker=".", c="orange", label="GENERATED-X") +axis[0, 0].legend(loc = 'upper right') +axis[0, 0].text(0.01, 0.99, "Error average:" + format(average[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) +axis[0, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[0], '+.2e') + unit, verticalalignment = 'top', transform = axis[0, 0].transAxes) + +axis[1, 0].plot(time[0], ordered_force_b_N[1], marker=".", c="green", label="ORDERED-Y") +axis[1, 0].plot(time[0], generated_force_b_N[1], marker=".", c="yellow", label="GENERATED-Y") +axis[1, 0].legend(loc = 'upper right') +axis[1, 0].text(0.01, 0.99, "Error average:" + format(average[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) +axis[1, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[1], '+.2e') + unit, verticalalignment = 'top', transform = axis[1, 0].transAxes) + +axis[2, 0].plot(time[0], ordered_force_b_N[2], marker=".", c="blue", label="ORDERED-Z") +axis[2, 0].plot(time[0], generated_force_b_N[2], marker=".", c="purple", label="GENERATED-Z") +axis[2, 0].legend(loc = 'upper right') +axis[2, 0].text(0.01, 0.99, "Error average:" + format(average[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) +axis[2, 0].text(0.01, 0.89, "Standard deviation:" + format(standard_deviation[2], '+.2e') + unit, verticalalignment = 'top', transform = axis[2, 0].transAxes) + +fig.suptitle("Torque Generator Output @ Body frame") +fig.supylabel("Torque" + unit) +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_torque_generator.png") # save last figure only +else: + plt.show() From 2b3e71e76db524d274c93950c87df6bb137028e3 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 2 Mar 2023 15:26:51 +0100 Subject: [PATCH 0996/1086] Add plot for Ground Station Calculator --- .../Plot/plot_ground_station_calculator.py | 77 +++++++++++++++++++ 1 file changed, 77 insertions(+) create mode 100644 scripts/Plot/plot_ground_station_calculator.py diff --git a/scripts/Plot/plot_ground_station_calculator.py b/scripts/Plot/plot_ground_station_calculator.py new file mode 100644 index 000000000..c339960e8 --- /dev/null +++ b/scripts/Plot/plot_ground_station_calculator.py @@ -0,0 +1,77 @@ +# +# Plot Ground station calculator +# +# arg[1] : read_file_tag : time tag for default CSV output log file. ex. 220627_142946 +# + +# +# Import +# +# plots +import matplotlib.pyplot as plt +# local function +from common import find_latest_log_tag +from common import add_log_file_arguments +from common import read_scalar_from_csv +# arguments +import argparse + +# Arguments +aparser = argparse.ArgumentParser() +aparser = add_log_file_arguments(aparser) +aparser.add_argument('--no-gui', action='store_true') +args = aparser.parse_args() + +# +# Read Arguments +# +# log file path +path_to_logs = args.logs_dir + +read_file_tag = args.file_tag +if read_file_tag == None: + print("file tag does not found. use latest.") + read_file_tag = find_latest_log_tag(path_to_logs) + +print("log: " + read_file_tag) + +# +# CSV file name +# +read_file_name = path_to_logs + '/' + 'logs_' + read_file_tag + '/' + read_file_tag + '_default.csv' + +# +# Data read and edit +# +# Read S2E CSV +time = read_scalar_from_csv(read_file_name, 'elapsed_time[s]') +sc0_visible_flag = read_scalar_from_csv(read_file_name, 'ground_station0_sc0_visible_flag') +max_bitrate_Mbps = read_scalar_from_csv(read_file_name, 'gs_calculator_max_bitrate[Mbps]') +receive_margin_dB = read_scalar_from_csv(read_file_name, 'gs_calculator_receive_margin[dB]') + +# +# Plot +# +unit = ' Nm' + +fig, axis = plt.subplots(3, 1, squeeze = False, tight_layout = True, sharex = True) +axis[0, 0].plot(time[0], sc0_visible_flag[0], marker=".", c="red", label="SC0-VSIBLE") +axis[0, 0].legend(loc = 'upper right') +axis[0, 0].set(ylabel = 'Visible Flag') + +axis[1, 0].plot(time[0], max_bitrate_Mbps[0], marker=".", c="green", label="Mbps") +axis[1, 0].legend(loc = 'upper right') +axis[1, 0].set(ylabel = 'Max bitrate [Mbps]') + +axis[2, 0].plot(time[0], receive_margin_dB[0], marker=".", c="blue", label="dB") +axis[2, 0].legend(loc = 'upper right') +axis[2, 0].set(ylabel = 'Receive margin [dB]') + +fig.suptitle("Ground Station") +fig.supxlabel("Time [s]") + +# Data save +if args.no_gui: + plt.savefig(read_file_tag + "_ground_station_calculator.png") # save last figure only +else: + plt.show() From e168261dbb968d8efdaee393ad5750bb543b30bd Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 09:36:11 +0100 Subject: [PATCH 0997/1086] Move Vector::FillUp to member function --- src/dynamics/orbit/encke_orbit_propagation.cpp | 6 +++--- .../math/matrix_vector_template_functions.hpp | 2 +- src/library/math/vector.cpp | 2 +- src/library/math/vector.hpp | 17 ++++++++--------- src/library/math/vector_template_functions.hpp | 4 ++-- 5 files changed, 15 insertions(+), 16 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index d2c9028ac..b3d81dcad 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -85,7 +85,7 @@ void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& // Private Functions void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> reference_position_i_m, libra::Vector<3> reference_velocity_i_m_s) { // General - FillUp(spacecraft_acceleration_i_m_s2_, 0.0); + spacecraft_acceleration_i_m_s2_.FillUp(0.0); // reference orbit reference_position_i_m_ = reference_position_i_m; @@ -94,8 +94,8 @@ void EnckeOrbitPropagation::Initialize(double current_time_jd, libra::Vector<3> reference_kepler_orbit = KeplerOrbit(gravity_constant_m3_s2_, oe_ref); // difference orbit - FillUp(difference_position_i_m_, 0.0); - FillUp(difference_velocity_i_m_s_, 0.0); + difference_position_i_m_.FillUp(0.0); + difference_velocity_i_m_s_.FillUp(0.0); libra::Vector<6> zero(0.0f); Setup(0.0, zero); diff --git a/src/library/math/matrix_vector_template_functions.hpp b/src/library/math/matrix_vector_template_functions.hpp index f84d3311d..db53e0ef6 100644 --- a/src/library/math/matrix_vector_template_functions.hpp +++ b/src/library/math/matrix_vector_template_functions.hpp @@ -30,7 +30,7 @@ Matrix CalcInverseMatrix(const Matrix& matrix) { Matrix inverse; Vector vector; for (size_t i = 0; i < N; ++i) { - FillUp(vector, 0.0); + vector.FillUp(0.0); vector[i] = 1.0; SolveLinearSystemWithLu(temp, index, vector); for (size_t j = 0; j < N; ++j) { diff --git a/src/library/math/vector.cpp b/src/library/math/vector.cpp index cbfd5e54a..11d2943af 100644 --- a/src/library/math/vector.cpp +++ b/src/library/math/vector.cpp @@ -10,7 +10,7 @@ namespace libra { Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& orthogonal) { Vector<3, double> polar; // vector on the polar coordinate - FillUp(polar, 0.0); + polar.FillUp(0.0); polar[0] = CalcNorm(orthogonal); // Skip when zero vector if (polar[0] == 0.0) { diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index f6ee24c43..c90d73342 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -38,6 +38,14 @@ class Vector { */ inline size_t GetLength() const { return N; } + /** + * @fn FillUp + * @brief Fill up all elements with same value + * @param [in] v: Target vector + * @param [in] n: Scalar value to fill up + */ + void FillUp(const T& n); + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 1D-array using `[]` @@ -127,15 +135,6 @@ class Vector { T vector_[N]; //!< Array to store elements }; -/** - * @fn FillUp - * @brief Fill up all elements with same value - * @param [in] v: Target vector - * @param [in] n: Scalar value to fill up - */ -template -void FillUp(Vector& v, const T& n); - /** * @fn Print * @brief Generate all elements to outstream diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index 9a41219dc..6178a6276 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -54,9 +54,9 @@ Vector Vector::operator-() const { } template -void FillUp(Vector& v, const T& n) { +void Vector::FillUp(const T& n) { for (size_t i = 0; i < N; ++i) { - v[i] = n; + vector_[i] = n; } } From c36b2d60c0e2f058f6aabed8e371499cc575e9a7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 09:38:04 +0100 Subject: [PATCH 0998/1086] Move Vector::Print to member function --- src/library/math/vector.hpp | 19 +++++++++---------- .../math/vector_template_functions.hpp | 6 +++--- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index c90d73342..3282ce8e5 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -46,6 +46,15 @@ class Vector { */ void FillUp(const T& n); + /** + * @fn Print + * @brief Generate all elements to outstream + * @param [in] v: Target vector + * @param [in] delimiter: Delimiter (Default: tab) + * @param [out] stream: Output target(Default: cout) + */ + void Print(char delimiter = '\t', std::ostream& stream = std::cout); + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 1D-array using `[]` @@ -135,16 +144,6 @@ class Vector { T vector_[N]; //!< Array to store elements }; -/** - * @fn Print - * @brief Generate all elements to outstream - * @param [in] v: Target vector - * @param [in] delimiter: Delimiter (Default: tab) - * @param [out] stream: Output target(Default: cout) - */ -template -void Print(const Vector& v, char delimiter = '\t', std::ostream& stream = std::cout); - /** * @fn operator + * @brief Add two vectors diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index 6178a6276..5f7c87599 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -61,10 +61,10 @@ void Vector::FillUp(const T& n) { } template -void Print(const Vector& v, char delimiter, std::ostream& stream) { - stream << v[0]; +void Vector::Print(char delimiter, std::ostream& stream) { + stream << vector_[0]; for (size_t i = 1; i < N; ++i) { - stream << delimiter << v[i]; + stream << delimiter << vector_[i]; } } From 58e159ad4f1be4dcd1932e49e85ce2e6ed56f4c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 11:07:41 +0100 Subject: [PATCH 0999/1086] Move Vector::CalcNorm to member function --- src/components/ideal/force_generator.cpp | 4 ++-- src/components/ideal/torque_generator.cpp | 4 ++-- src/components/real/aocs/gnss_receiver.cpp | 6 +++--- src/components/real/aocs/star_sensor.cpp | 4 ++-- .../communication/ground_station_calculator.cpp | 4 +++- .../real/propulsion/simple_thruster.cpp | 2 +- src/disturbances/air_drag.cpp | 4 ++-- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/third_body_gravity.cpp | 4 ++-- src/dynamics/attitude/attitude.cpp | 2 +- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/orbit/encke_orbit_propagation.cpp | 6 +++--- src/dynamics/orbit/relative_orbit.cpp | 4 ++-- src/dynamics/thermal/node.cpp | 4 ++-- src/dynamics/thermal/temperature.cpp | 2 +- .../solar_radiation_pressure_environment.cpp | 12 ++++++------ src/library/math/quaternion.cpp | 12 ++++++------ src/library/math/vector.cpp | 2 +- src/library/math/vector.hpp | 17 ++++++++--------- src/library/math/vector_template_functions.hpp | 10 +++++----- src/library/orbit/orbital_elements.cpp | 4 ++-- .../initialize_monte_carlo_parameters.cpp | 6 +++--- .../relative_information.cpp | 4 ++-- .../structure/initialize_structure.cpp | 2 +- 24 files changed, 62 insertions(+), 61 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 458bb0f49..6ea2bd947 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -25,7 +25,7 @@ void ForceGenerator::MainRoutine(const int time_count) { generated_force_b_N_ = ordered_force_b_N_; // Add noise - double norm_ordered_force = CalcNorm(ordered_force_b_N_); + double norm_ordered_force = ordered_force_b_N_.CalcNorm(); if (norm_ordered_force > 0.0 + DBL_EPSILON) { // Add noise only when the force is generated libra::Vector<3> true_direction = Normalize(generated_force_b_N_); @@ -93,7 +93,7 @@ libra::Quaternion ForceGenerator::GenerateDirectionNoiseQuaternion(libra::Vector libra::Vector<3> rotation_axis; rotation_axis = OuterProduct(true_direction, random_direction); - double norm_rotation_axis = CalcNorm(rotation_axis); + double norm_rotation_axis = rotation_axis.CalcNorm(); if (norm_rotation_axis < 0.0 + DBL_EPSILON) { // No rotation error if the randomized direction is parallel to the true direction rotation_axis = true_direction; diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index f160a2c04..5aa85336e 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -25,7 +25,7 @@ void TorqueGenerator::MainRoutine(const int time_count) { generated_torque_b_Nm_ = ordered_torque_b_Nm_; // Add noise - double norm_ordered_torque = CalcNorm(ordered_torque_b_Nm_); + double norm_ordered_torque = ordered_torque_b_Nm_.CalcNorm(); if (norm_ordered_torque > 0.0 + DBL_EPSILON) { // Add noise only when the torque is generated libra::Vector<3> true_direction = Normalize(generated_torque_b_Nm_); @@ -66,7 +66,7 @@ libra::Quaternion TorqueGenerator::GenerateDirectionNoiseQuaternion(libra::Vecto libra::Vector<3> rotation_axis; rotation_axis = OuterProduct(true_direction, random_direction); - double norm_rotation_axis = CalcNorm(rotation_axis); + double norm_rotation_axis = rotation_axis.CalcNorm(); if (norm_rotation_axis < 0.0 + DBL_EPSILON) { // No rotation error if the randomized direction is parallel to the true direction rotation_axis = true_direction; diff --git a/src/components/real/aocs/gnss_receiver.cpp b/src/components/real/aocs/gnss_receiver.cpp index afb7d6996..c8520ccc5 100644 --- a/src/components/real/aocs/gnss_receiver.cpp +++ b/src/components/real/aocs/gnss_receiver.cpp @@ -121,7 +121,7 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: // compute direction from sat to gnss in body-fixed frame gnss_sat_pos_i = gnss_satellites_->GetSatellitePositionEci(i); antenna_to_satellite_i_m = gnss_sat_pos_i - ant_pos_i; - double normalizer = 1 / CalcNorm(antenna_to_satellite_i_m); + double normalizer = 1 / antenna_to_satellite_i_m.CalcNorm(); ant2gnss_i_n = normalizer * antenna_to_satellite_i_m; // check gnss sats are visible from antenna @@ -132,7 +132,7 @@ void GnssReceiver::CheckAntennaCone(const libra::Vector<3> pos_true_eci_, libra: is_visible_ant2gnss = 1; else { Vector<3> tmp = ant_pos_i + InnerProduct(-ant_pos_i, ant2gnss_i_n) * antenna_to_satellite_i_m; - if (CalcNorm(tmp) < Re) + if (tmp.CalcNorm() < Re) // There is earth between antenna and gnss is_visible_ant2gnss = 0; else @@ -160,7 +160,7 @@ void GnssReceiver::SetGnssInfo(libra::Vector<3> antenna_to_satellite_i_m, libra: ant2gnss_b = quaternion_i2b.FrameConversion(antenna_to_satellite_i_m); ant2gnss_c = quaternion_b2c_.FrameConversion(ant2gnss_b); - double dist = CalcNorm(ant2gnss_c); + double dist = ant2gnss_c.CalcNorm(); double lon = AcTan(ant2gnss_c[1], ant2gnss_c[0]); double lat = AcTan(ant2gnss_c[2], sqrt(pow(ant2gnss_c[0], 2.0) + pow(ant2gnss_c[1], 2.0))); diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index eaa4613e4..f1ac8debf 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -150,7 +150,7 @@ int StarSensor::EarthJudgement(const libra::Vector<3>& earth_b) { libra::Quaternion q_c2b = quaternion_b2c_.Conjugate(); libra::Vector<3> sight_b = q_c2b.FrameConversion(sight_direction_c_); double earth_size_rad = atan2(environment::earth_equatorial_radius_m, - CalcNorm(earth_b)); // angles between sat<->earth_center & sat<->earth_edge + earth_b.CalcNorm()); // angles between sat<->earth_center & sat<->earth_edge double earth_center_angle_rad = CalAngleVector_rad(earth_b, sight_b); // angles between sat<->earth_center & sat_sight double earth_edge_angle_rad = earth_center_angle_rad - earth_size_rad; // angles between sat<->earth_edge & sat_sight if (earth_edge_angle_rad < earth_forbidden_angle_rad_) @@ -170,7 +170,7 @@ int StarSensor::MoonJudgement(const libra::Vector<3>& moon_b) { } int StarSensor::CaptureRateJudgement(const libra::Vector<3>& omega_b_rad_s) { - double omega_norm = CalcNorm(omega_b_rad_s); + double omega_norm = omega_b_rad_s.CalcNorm(); if (omega_norm > capture_rate_limit_rad_s_) return 1; else diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index e21058fd8..5b706117c 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -69,7 +69,9 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); - double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; + Vector<3> pos_gs2sc_i = sc_pos_i - gs_pos_i; + + double dist_sc_gs_km = pos_gs2sc_i.CalcNorm() / 1000.0; double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_tx_antenna.GetFrequency_MHz() / 1000.0)); // GS direction on SC TX antenna frame diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index b5eaba08c..b1227b573 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -87,7 +87,7 @@ std::string SimpleThruster::GetLogValue() const { str_tmp += WriteVector(output_thrust_b_N_); str_tmp += WriteVector(output_torque_b_Nm_); - str_tmp += WriteScalar(CalcNorm(output_thrust_b_N_)); + str_tmp += WriteScalar(output_thrust_b_N_.CalcNorm()); return str_tmp; } diff --git a/src/disturbances/air_drag.cpp b/src/disturbances/air_drag.cpp index 0a06d062d..5f2264135 100644 --- a/src/disturbances/air_drag.cpp +++ b/src/disturbances/air_drag.cpp @@ -29,7 +29,7 @@ void AirDrag::Update(const LocalEnvironment& local_environment, const Dynamics& } void AirDrag::CalcCoefficients(const libra::Vector<3>& velocity_b_m_s, const double air_density_kg_m3) { - double velocity_norm_m_s = CalcNorm(velocity_b_m_s); + double velocity_norm_m_s = velocity_b_m_s.CalcNorm(); CalcCnCt(velocity_b_m_s); for (size_t i = 0; i < surfaces_.size(); i++) { double k = 0.5 * air_density_kg_m3 * velocity_norm_m_s * velocity_norm_m_s * surfaces_[i].GetArea_m2(); @@ -53,7 +53,7 @@ double AirDrag::CalcFunctionChi(const double s) { } void AirDrag::CalcCnCt(const Vector<3>& velocity_b_m_s) { - double velocity_norm_m_s = CalcNorm(velocity_b_m_s); + double velocity_norm_m_s = velocity_b_m_s.CalcNorm(); // Re-emitting speed double speed = diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 7390771db..0711e3071 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -24,7 +24,7 @@ void GravityGradient::Update(const LocalEnvironment& local_environment, const Dy libra::Vector<3> GravityGradient::CalcTorque_b_Nm(const libra::Vector<3> earth_position_from_sc_b_m, const libra::Matrix<3, 3> inertia_tensor_b_kgm2) { - double r_norm_m = CalcNorm(earth_position_from_sc_b_m); + double r_norm_m = earth_position_from_sc_b_m.CalcNorm(); libra::Vector<3> u_b = earth_position_from_sc_b_m; // TODO: make undestructive normalize function for Vector u_b /= r_norm_m; diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 61f3a358a..2f8ebf28f 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -29,10 +29,10 @@ void ThirdBodyGravity::Update(const LocalEnvironment& local_environment, const D libra::Vector<3> ThirdBodyGravity::CalcAcceleration_i_m_s2(const libra::Vector<3> s, const libra::Vector<3> sr, const double gravity_constant_m_s2) { libra::Vector<3> acceleration_i_m_s2; - double s_norm = libra::CalcNorm(s); + double s_norm = s.CalcNorm(); double s_norm3 = s_norm * s_norm * s_norm; - double sr_norm = libra::CalcNorm(sr); + double sr_norm = sr.CalcNorm(); double sr_norm3 = sr_norm * sr_norm * sr_norm; acceleration_i_m_s2 = gravity_constant_m_s2 * (1.0 / sr_norm3 * sr - 1.0 / s_norm3 * s); diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 5b07380e9..01eabf378 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -51,7 +51,7 @@ void Attitude::CalcAngularMomentum(void) { angular_momentum_total_b_Nms_ = angular_momentum_reaction_wheel_b_Nms_ + angular_momentum_spacecraft_b_Nms_; libra::Quaternion q_b2i = quaternion_i2b_.Conjugate(); angular_momentum_total_i_Nms_ = q_b2i.FrameConversion(angular_momentum_total_b_Nms_); - angular_momentum_total_Nms_ = CalcNorm(angular_momentum_total_i_Nms_); + angular_momentum_total_Nms_ = angular_momentum_total_i_Nms_.CalcNorm(); kinetic_energy_J_ = 0.5 * libra::InnerProduct(angular_momentum_spacecraft_b_Nms_, angular_velocity_b_rad_s_); } diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 570e3918a..2670e92ab 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -50,7 +50,7 @@ class Attitude : public ILoggable, public SimulationObject { * @fn GetTotalAngularMomentNorm_Nms * @brief Return norm of total angular momentum of the spacecraft [Nms] */ - inline double GetTotalAngularMomentNorm_Nms() const { return libra::CalcNorm(angular_momentum_total_b_Nms_); } + inline double GetTotalAngularMomentNorm_Nms() const { return angular_momentum_total_b_Nms_.CalcNorm(); } /** * @fn GetKineticEnergy_J * @brief Return rotational Kinetic Energy of Spacecraft [J] diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index b3d81dcad..4f8c4fbde 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -28,8 +28,8 @@ void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) if (!is_calc_enabled_) return; // Rectification - double norm_sat_position_m = CalcNorm(spacecraft_position_i_m_); - double norm_difference_position_m = CalcNorm(difference_position_i_m_); + double norm_sat_position_m = spacecraft_position_i_m_.CalcNorm(); + double norm_difference_position_m = difference_position_i_m_.CalcNorm(); if (norm_difference_position_m / norm_sat_position_m > error_tolerance_) { Initialize(current_time_jd, spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); } @@ -68,7 +68,7 @@ void EnckeOrbitPropagation::DerivativeFunction(double t, const libra::Vector<6>& } double q_func = CalcQFunction(difference_position_i_m_m); - double r_m = CalcNorm(reference_position_i_m_); + double r_m = reference_position_i_m_.CalcNorm(); double r_m3 = pow(r_m, 3.0); difference_acc_i_m_s2 = diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index a39c82f10..0a40909b7 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -71,7 +71,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m double gravity_constant_m3_s2) { switch (relative_dynamics_model_type) { case RelativeOrbitModel::Hill: { - double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); + double reference_sat_orbit_radius = reference_sat_orbit->GetPosition_i_m().CalcNorm(); system_matrix_ = CalcHillSystemMatrix(reference_sat_orbit_radius, gravity_constant_m3_s2); } default: { @@ -84,7 +84,7 @@ void RelativeOrbit::CalculateSystemMatrix(RelativeOrbitModel relative_dynamics_m void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference_sat_orbit, double gravity_constant_m3_s2, double elapsed_sec) { switch (stm_model_type) { case StmModel::HCW: { - double reference_sat_orbit_radius = libra::CalcNorm(reference_sat_orbit->GetPosition_i_m()); + double reference_sat_orbit_radius = reference_sat_orbit->GetPosition_i_m().CalcNorm(); stm_ = CalcHcwStm(reference_sat_orbit_radius, gravity_constant_m3_s2, elapsed_sec); } default: { diff --git a/src/dynamics/thermal/node.cpp b/src/dynamics/thermal/node.cpp index 2c1066718..5ad75151a 100644 --- a/src/dynamics/thermal/node.cpp +++ b/src/dynamics/thermal/node.cpp @@ -62,9 +62,9 @@ double Node::CalcSolarRadiation(libra::Vector<3> sun_direction) { double R = 6.96E+8; // Distance from sun double T = 5778; // sun surface temperature [K] double sigma = 5.67E-8; // stephan-boltzman constant - double a = CalcNorm(sun_direction); // distance from sun + double a = sun_direction.CalcNorm(); // distance from sun double S = pow((R / a), 2) * sigma * pow(T, 4); // Solar Constant at s/c position S[W/m^2] - double cos_theta = InnerProduct(sun_direction, normal_v_b_) / a / CalcNorm(normal_v_b_); + double cos_theta = InnerProduct(sun_direction, normal_v_b_) / a / normal_v_b_.CalcNorm(); // calculate sun_power if (cos_theta > 0) diff --git a/src/dynamics/thermal/temperature.cpp b/src/dynamics/thermal/temperature.cpp index 25a30fe9f..1ad1127f1 100644 --- a/src/dynamics/thermal/temperature.cpp +++ b/src/dynamics/thermal/temperature.cpp @@ -56,7 +56,7 @@ void Temperature::Propagate(libra::Vector<3> sun_direction, const double endtime cout << setprecision(4) << itr->GetSolarRadiation() << " "; } cout << "SunDir: "; - double norm_sund = CalcNorm(sun_direction); + double norm_sund = sun_direction.CalcNorm(); for (int i = 0; i < 3; i++) { cout << setprecision(3) << sun_direction[i] / norm_sund << " "; } diff --git a/src/environment/local/solar_radiation_pressure_environment.cpp b/src/environment/local/solar_radiation_pressure_environment.cpp index 877cfb882..d056e7292 100644 --- a/src/environment/local/solar_radiation_pressure_environment.cpp +++ b/src/environment/local/solar_radiation_pressure_environment.cpp @@ -28,7 +28,7 @@ void SolarRadiationPressureEnvironment::UpdateAllStates() { void SolarRadiationPressureEnvironment::UpdatePressure() { const libra::Vector<3> r_sc2sun_eci = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); - const double distance_sat_to_sun = CalcNorm(r_sc2sun_eci); + const double distance_sat_to_sun = r_sc2sun_eci.CalcNorm(); solar_radiation_pressure_N_m2_ = solar_constant_W_m2_ / environment::speed_of_light_m_s / pow(distance_sat_to_sun / environment::astronomical_unit_m, 2.0); } @@ -62,13 +62,13 @@ void SolarRadiationPressureEnvironment::CalcShadowCoefficient(std::string shadow const double shadow_source_radius_m = local_celestial_information_->GetGlobalInformation().GetMeanRadiusFromName_m(shadow_source_name.c_str()); - const double distance_sat_to_sun = CalcNorm(r_sc2sun_eci); - const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun - const double sd_source = asin(shadow_source_radius_m / CalcNorm(r_sc2source_eci)); // Apparent radius of the shadow source + const double distance_sat_to_sun = r_sc2sun_eci.CalcNorm(); + const double sd_sun = asin(sun_radius_m_ / distance_sat_to_sun); // Apparent radius of the sun + const double sd_source = asin(shadow_source_radius_m / r_sc2source_eci.CalcNorm()); // Apparent radius of the shadow source // Angle of deviation from shadow source center to sun center - const double delta = - acos(InnerProduct(r_sc2source_eci, r_sc2sun_eci - r_sc2source_eci) / CalcNorm(r_sc2source_eci) / CalcNorm(r_sc2sun_eci - r_sc2source_eci)); + libra::Vector<3> r_source2sun_eci = r_sc2sun_eci - r_sc2source_eci; + const double delta = acos(InnerProduct(r_sc2source_eci, r_sc2sun_eci - r_sc2source_eci) / r_sc2source_eci.CalcNorm() / r_source2sun_eci.CalcNorm()); // The angle between the center of the sun and the common chord const double x = (delta * delta + sd_sun * sd_sun - sd_source * sd_source) / (2.0 * delta); // The length of the common chord of the apparent solar disk and apparent telestial disk diff --git a/src/library/math/quaternion.cpp b/src/library/math/quaternion.cpp index 616c32418..a6b398a1c 100644 --- a/src/library/math/quaternion.cpp +++ b/src/library/math/quaternion.cpp @@ -24,11 +24,11 @@ Quaternion::Quaternion(const Vector<3>& rotation_axis, const double rotation_ang Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_after) { // Assert for zero vector - assert(CalcNorm(vector_before) > DBL_EPSILON); - assert(CalcNorm(vector_after) > DBL_EPSILON); + assert(vector_before.CalcNorm() > DBL_EPSILON); + assert(vector_after.CalcNorm() > DBL_EPSILON); // Normalize - Vector<3> normalized_v_before = 1.0 / CalcNorm(vector_before) * vector_before; - Vector<3> normalized_v_after = 1.0 / CalcNorm(vector_after) * vector_after; + Vector<3> normalized_v_before = 1.0 / vector_before.CalcNorm() * vector_before; + Vector<3> normalized_v_after = 1.0 / vector_after.CalcNorm() * vector_after; // inner product (=cosine of the CalcAngleTwoVectors_rad(theta) between two vectors) double ip = InnerProduct(normalized_v_before, normalized_v_after); // outer product (rotation rotation_axis for converting vector_before to vector_after) @@ -44,8 +44,8 @@ Quaternion::Quaternion(const Vector<3>& vector_before, const Vector<3>& vector_a Vector<3> rotation_axis = GenerateOrthogonalUnitVector(vector_before); quaternion_[0] = rotation_axis[0], quaternion_[1] = rotation_axis[1], quaternion_[2] = rotation_axis[2], quaternion_[3] = 0.0; } else { - assert(CalcNorm(op) > 0.0); - Vector<3> rotation_axis = 1.0 / CalcNorm(op) * op; + assert(op.CalcNorm() > 0.0); + Vector<3> rotation_axis = 1.0 / op.CalcNorm() * op; double rotation_angle = acos(ip); quaternion_[0] = rotation_axis[0] * sin(0.5 * rotation_angle); quaternion_[1] = rotation_axis[1] * sin(0.5 * rotation_angle); diff --git a/src/library/math/vector.cpp b/src/library/math/vector.cpp index 11d2943af..4df438a51 100644 --- a/src/library/math/vector.cpp +++ b/src/library/math/vector.cpp @@ -11,7 +11,7 @@ namespace libra { Vector<3, double> ConvertFrameOrthogonal2Polar(const Vector<3, double>& orthogonal) { Vector<3, double> polar; // vector on the polar coordinate polar.FillUp(0.0); - polar[0] = CalcNorm(orthogonal); + polar[0] = orthogonal.CalcNorm(); // Skip when zero vector if (polar[0] == 0.0) { return polar; diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 3282ce8e5..7d9677c15 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -55,6 +55,14 @@ class Vector { */ void Print(char delimiter = '\t', std::ostream& stream = std::cout); + /** + * @fn CalcNorm + * @brief Calculate norm of vector + * @param [in] v: Target vector + * @return Norm of the vector + */ + double CalcNorm() const; + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 1D-array using `[]` @@ -194,15 +202,6 @@ const T InnerProduct(const Vector& lhs, const Vector& rhs); template const Vector<3, T> OuterProduct(const Vector<3, T>& lhs, const Vector<3, T>& rhs); -/** - * @fn CalcNorm - * @brief Calculate norm of vector - * @param [in] v: Target vector - * @return Norm of the vector - */ -template -double CalcNorm(const Vector& v); - /** * @fn Normalize * @brief Normalize the target vector diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index 5f7c87599..48efcc57a 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -113,18 +113,18 @@ const Vector<3, T> OuterProduct(const Vector<3, T>& lhs, const Vector<3, T>& rhs return temp; } -template -double CalcNorm(const Vector& v) { +template +double Vector::CalcNorm() const { double temp = 0.0; for (size_t i = 0; i < N; ++i) { - temp += pow(v[i], 2.0); + temp += pow((double)vector_[i], 2.0); } return sqrt(temp); } template Vector& Normalize(Vector& v) { - double n = CalcNorm(v); + double n = v.CalcNorm(); if (n == 0.0) { return v; } @@ -139,7 +139,7 @@ Vector& Normalize(Vector& v) { template double CalcAngleTwoVectors_rad(const Vector& v1, const Vector& v2) { - double cos = InnerProduct(v1, v2) / (CalcNorm(v1) * CalcNorm(v2)); + double cos = InnerProduct(v1, v2) / (v1.CalcNorm() * v2.CalcNorm()); return acos(cos); } diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index 5bc32b105..97a9abef3 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -33,11 +33,11 @@ OrbitalElements::~OrbitalElements() {} void OrbitalElements::CalcOeFromPosVel(const double gravity_constant_m3_s2, const double time_jday, const libra::Vector<3> position_i_m, const libra::Vector<3> velocity_i_m_s) { // common variables - double r_m = CalcNorm(position_i_m); + double r_m = position_i_m.CalcNorm(); double v2_m2_s2 = InnerProduct(velocity_i_m_s, velocity_i_m_s); libra::Vector<3> h; //!< angular momentum vector h = OuterProduct(position_i_m, velocity_i_m_s); - double h_norm = CalcNorm(h); + double h_norm = h.CalcNorm(); // semi major axis semi_major_axis_m_ = gravity_constant_m3_s2 / (2.0 * gravity_constant_m3_s2 / r_m - v2_m2_s2); diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index c4a26c8d0..70cbab799 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -195,7 +195,7 @@ void InitializedMonteCarloParameters::GenerateSphericalNormalUniformUniform() { void InitializedMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3>& destination, const libra::Vector<3>& mean_vec) { // r and θ follow normal distribution, and mean vector angle φ follows uniform distribution [0,2*pi] libra::Vector<3> mean_vec_dir; - mean_vec_dir = 1.0 / CalcNorm(mean_vec) * mean_vec; // Unit vector of mean vector direction + mean_vec_dir = 1.0 / mean_vec.CalcNorm() * mean_vec; // Unit vector of mean vector direction libra::Vector<3> x_axis(0.0), y_axis(0.0); x_axis[0] = 1.0; @@ -205,7 +205,7 @@ void InitializedMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3> // An unit vector perpendicular with the mean vector // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product - libra::Vector<3> normal_unit_vec = CalcNorm(op_x) > CalcNorm(op_y) ? Normalize(op_x) : Normalize(op_y); + libra::Vector<3> normal_unit_vec = op_x.CalcNorm() > op_y.CalcNorm() ? Normalize(op_x) : Normalize(op_y); double rotation_angle_of_normal_unit_vec = InitializedMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, @@ -216,7 +216,7 @@ void InitializedMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3> libra::Quaternion rotation_of_mean_vec(rotation_axis, -rotation_angle_of_mean_vec); // Use opposite sign to rotate the vector (not the frame) libra::Vector<3> ret_vec = rotation_of_mean_vec.FrameConversion(mean_vec_dir); // Complete calculation of the direction - ret_vec = InitializedMonteCarloParameters::Generate1dNormal(CalcNorm(mean_vec), sigma_or_max_[0]) * ret_vec; // multiply norm + ret_vec = InitializedMonteCarloParameters::Generate1dNormal(mean_vec.CalcNorm(), sigma_or_max_[0]) * ret_vec; // multiply norm for (int i = 0; i < 3; i++) { destination[i] = ret_vec[i]; diff --git a/src/simulation/multiple_spacecraft/relative_information.cpp b/src/simulation/multiple_spacecraft/relative_information.cpp index bc62533e2..290eb5e26 100644 --- a/src/simulation/multiple_spacecraft/relative_information.cpp +++ b/src/simulation/multiple_spacecraft/relative_information.cpp @@ -21,7 +21,7 @@ void RelativeInformation::Update() { // Distance relative_distance_list_m_[target_spacecraft_id][reference_spacecraft_id] = - CalcNorm(relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id]); + relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id].CalcNorm(); // Velocity libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); @@ -144,7 +144,7 @@ libra::Vector<3> RelativeInformation::CalcRelativeVelocity_rtn_m_s(const int tar libra::Vector<3> reference_sat_vel_i = dynamics_database_.at(reference_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> target_sat_vel_i = dynamics_database_.at(target_spacecraft_id)->GetOrbit().GetVelocity_i_m_s(); libra::Vector<3> rot_vec_rtn_i = cross(reference_sat_pos_i, reference_sat_vel_i); - double r2_ref = CalcNorm(reference_sat_pos_i) * CalcNorm(reference_sat_pos_i); + double r2_ref = reference_sat_pos_i.CalcNorm() * reference_sat_pos_i.CalcNorm(); rot_vec_rtn_i /= r2_ref; libra::Vector<3> relative_vel_i = target_sat_vel_i - reference_sat_vel_i - cross(rot_vec_rtn_i, relative_pos_i); diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 18a791279..44ea055b4 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -93,7 +93,7 @@ std::vector InitSurfaces(std::string file_name) { keyword = "normal_vector" + idx + "_b"; conf.ReadVector(section, keyword.c_str(), normal); - if (CalcNorm(normal) > 1.0 + MIN_VAL) // Fixme: magic word + if (normal.CalcNorm() > 1.0 + MIN_VAL) // Fixme: magic word { cout << "Surface Warning! " << keyword << ": norm is larger than 1.0."; cout << "The vector is normalized.\n"; From 95a034a4549bda649fd2179ba910e21803332342 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 11:09:24 +0100 Subject: [PATCH 1000/1086] Fix comments to describe functions --- src/library/math/vector.hpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 7d9677c15..2bca9f28e 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -33,7 +33,7 @@ class Vector { explicit Vector(const T& n); /** - * @fn dim + * @fn GetLength * @brief Return number of elements */ inline size_t GetLength() const { return N; } @@ -41,7 +41,6 @@ class Vector { /** * @fn FillUp * @brief Fill up all elements with same value - * @param [in] v: Target vector * @param [in] n: Scalar value to fill up */ void FillUp(const T& n); @@ -49,7 +48,6 @@ class Vector { /** * @fn Print * @brief Generate all elements to outstream - * @param [in] v: Target vector * @param [in] delimiter: Delimiter (Default: tab) * @param [out] stream: Output target(Default: cout) */ @@ -58,7 +56,6 @@ class Vector { /** * @fn CalcNorm * @brief Calculate norm of vector - * @param [in] v: Target vector * @return Norm of the vector */ double CalcNorm() const; From 69251b6a1a4a4d2329c9c180b6e48909b497c03a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 12:33:40 +0100 Subject: [PATCH 1001/1086] Move Vector::Normalize to member function --- src/components/ideal/force_generator.cpp | 4 ++-- src/components/ideal/torque_generator.cpp | 4 ++-- src/components/real/aocs/star_sensor.cpp | 7 +++---- src/components/real/aocs/sun_sensor.cpp | 8 +++---- .../ground_station_calculator.cpp | 4 ++-- .../real/power/solar_array_panel.cpp | 10 ++++----- .../real/propulsion/simple_thruster.cpp | 2 +- src/disturbances/surface_force.cpp | 8 +++---- src/dynamics/attitude/controlled_attitude.cpp | 10 ++++----- src/dynamics/orbit/orbit.cpp | 6 +++--- src/library/math/vector.cpp | 6 +++--- src/library/math/vector.hpp | 19 ++++++++--------- .../math/vector_template_functions.hpp | 21 +++++++++++-------- src/library/orbit/orbital_elements.cpp | 3 +-- .../ground_station/ground_station.cpp | 2 +- .../initialize_monte_carlo_parameters.cpp | 2 +- .../structure/initialize_structure.cpp | 2 +- .../spacecraft/structure/surface.hpp | 5 +---- 18 files changed, 59 insertions(+), 64 deletions(-) diff --git a/src/components/ideal/force_generator.cpp b/src/components/ideal/force_generator.cpp index 6ea2bd947..0adbea835 100644 --- a/src/components/ideal/force_generator.cpp +++ b/src/components/ideal/force_generator.cpp @@ -28,7 +28,7 @@ void ForceGenerator::MainRoutine(const int time_count) { double norm_ordered_force = ordered_force_b_N_.CalcNorm(); if (norm_ordered_force > 0.0 + DBL_EPSILON) { // Add noise only when the force is generated - libra::Vector<3> true_direction = Normalize(generated_force_b_N_); + libra::Vector<3> true_direction = generated_force_b_N_.CalcNormalizedVector(); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_force_b_N_); double force_norm_with_error = norm_ordered_force + magnitude_noise_; @@ -89,7 +89,7 @@ libra::Quaternion ForceGenerator::GenerateDirectionNoiseQuaternion(libra::Vector random_direction[0] = direction_noise_; random_direction[1] = direction_noise_; random_direction[2] = direction_noise_; - random_direction = Normalize(random_direction); + random_direction = random_direction.CalcNormalizedVector(); libra::Vector<3> rotation_axis; rotation_axis = OuterProduct(true_direction, random_direction); diff --git a/src/components/ideal/torque_generator.cpp b/src/components/ideal/torque_generator.cpp index 5aa85336e..8762ad37a 100644 --- a/src/components/ideal/torque_generator.cpp +++ b/src/components/ideal/torque_generator.cpp @@ -28,7 +28,7 @@ void TorqueGenerator::MainRoutine(const int time_count) { double norm_ordered_torque = ordered_torque_b_Nm_.CalcNorm(); if (norm_ordered_torque > 0.0 + DBL_EPSILON) { // Add noise only when the torque is generated - libra::Vector<3> true_direction = Normalize(generated_torque_b_Nm_); + libra::Vector<3> true_direction = generated_torque_b_Nm_.CalcNormalizedVector(); libra::Quaternion error_quaternion = GenerateDirectionNoiseQuaternion(true_direction, direction_error_standard_deviation_rad_); libra::Vector<3> converted_direction = error_quaternion.FrameConversion(generated_torque_b_Nm_); double torque_norm_with_error = norm_ordered_torque + magnitude_noise_; @@ -62,7 +62,7 @@ libra::Quaternion TorqueGenerator::GenerateDirectionNoiseQuaternion(libra::Vecto random_direction[0] = direction_noise_; random_direction[1] = direction_noise_; random_direction[2] = direction_noise_; - random_direction = Normalize(random_direction); + random_direction = random_direction.CalcNormalizedVector(); libra::Vector<3> rotation_axis; rotation_axis = OuterProduct(true_direction, random_direction); diff --git a/src/components/real/aocs/star_sensor.cpp b/src/components/real/aocs/star_sensor.cpp index f1ac8debf..14f8fcbcd 100644 --- a/src/components/real/aocs/star_sensor.cpp +++ b/src/components/real/aocs/star_sensor.cpp @@ -198,10 +198,9 @@ std::string StarSensor::GetLogValue() const { } double StarSensor::CalAngleVector_rad(const Vector<3>& vector1, const Vector<3>& vector2) { - libra::Vector<3> vect1_normal(vector1); - Normalize(vect1_normal); // Normalize Vector1 - libra::Vector<3> vect2_normal(vector2); - Normalize(vect2_normal); // Normalize Vector2 + libra::Vector<3> vect1_normal = vector1.CalcNormalizedVector(); + libra::Vector<3> vect2_normal = vector2.CalcNormalizedVector(); + double cosTheta = InnerProduct(vect1_normal, vect2_normal); // Calc cos value double theta_rad = acos(cosTheta); return theta_rad; diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index a3a18de7d..336aceeab 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -59,7 +59,7 @@ void SunSensor::MainRoutine(const int time_count) { void SunSensor::Measure() { libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); - libra::Vector<3> sun_dir_b = Normalize(sun_pos_b); + libra::Vector<3> sun_dir_b = sun_pos_b.CalcNormalizedVector(); sun_direction_true_c_ = quaternion_b2c_.FrameConversion(sun_dir_b); // Frame conversion from body to component @@ -84,7 +84,7 @@ void SunSensor::Measure() { measured_sun_direction_c_[1] = tan(beta_rad_); measured_sun_direction_c_[2] = 1.0; - measured_sun_direction_c_ = Normalize(measured_sun_direction_c_); + measured_sun_direction_c_ = measured_sun_direction_c_.CalcNormalizedVector(); } else { measured_sun_direction_c_ = libra::Vector<3>(0); alpha_rad_ = 0.0; @@ -95,7 +95,7 @@ void SunSensor::Measure() { } void SunSensor::SunDetectionJudgement() { - libra::Vector<3> sun_direction_c = Normalize(sun_direction_true_c_); + libra::Vector<3> sun_direction_c = sun_direction_true_c_.CalcNormalizedVector(); double sun_angle_ = acos(sun_direction_c[2]); @@ -111,7 +111,7 @@ void SunSensor::SunDetectionJudgement() { } void SunSensor::CalcSolarIlluminance() { - libra::Vector<3> sun_direction_c = Normalize(sun_direction_true_c_); + libra::Vector<3> sun_direction_c = sun_direction_true_c_.CalcNormalizedVector(); double sun_angle_ = acos(sun_direction_c[2]); if (sun_angle_ > libra::pi_2) { diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 5b706117c..5291dfdae 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -76,7 +76,7 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; - sc_to_gs_i = libra::Normalize(sc_to_gs_i); + sc_to_gs_i = sc_to_gs_i.CalcNormalizedVector(); Quaternion q_i_to_sc_ant = spacecraft_tx_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[2]); @@ -84,7 +84,7 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetPosition_ecef_m(); - gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); + gs_to_sc_ecef = gs_to_sc_ecef.CalcNormalizedVector(); Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); diff --git a/src/components/real/power/solar_array_panel.cpp b/src/components/real/power/solar_array_panel.cpp index bd5532de4..711c00447 100644 --- a/src/components/real/power/solar_array_panel.cpp +++ b/src/components/real/power/solar_array_panel.cpp @@ -17,7 +17,7 @@ SolarArrayPanel::SolarArrayPanel(const int prescaler, ClockGenerator* clock_gene number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_m2_(cell_area_m2), - normal_vector_(libra::Normalize(normal_vector)), + normal_vector_(normal_vector.CalcNormalizedVector()), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_environment_(srp_environment), @@ -35,7 +35,7 @@ SolarArrayPanel::SolarArrayPanel(const int prescaler, ClockGenerator* clock_gene number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_m2_(cell_area_m2), - normal_vector_(libra::Normalize(normal_vector)), + normal_vector_(normal_vector.CalcNormalizedVector()), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_environment_(srp_environment), @@ -53,7 +53,7 @@ SolarArrayPanel::SolarArrayPanel(ClockGenerator* clock_generator, int component_ number_of_series_(number_of_series), number_of_parallel_(number_of_parallel), cell_area_m2_(cell_area_m2), - normal_vector_(libra::Normalize(normal_vector)), + normal_vector_(normal_vector.CalcNormalizedVector()), cell_efficiency_(cell_efficiency), transmission_efficiency_(transmission_efficiency), srp_environment_(srp_environment), @@ -99,13 +99,13 @@ void SolarArrayPanel::MainRoutine(const int time_count) { double time_query = compo_step_time_s_ * time_count; const auto solar_constant = srp_environment_->GetSolarConstant_W_m2(); libra::Vector<3> sun_direction_body = CsvScenarioInterface::GetSunDirectionBody(time_query); - libra::Vector<3> normalized_sun_direction_body = libra::Normalize(sun_direction_body); + libra::Vector<3> normalized_sun_direction_body = sun_direction_body.CalcNormalizedVector(); power_generation_W_ = cell_efficiency_ * transmission_efficiency_ * solar_constant * (int)CsvScenarioInterface::GetSunFlag(time_query) * cell_area_m2_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, normalized_sun_direction_body); } else { const auto power_density = srp_environment_->GetPowerDensity_W_m2(); libra::Vector<3> sun_pos_b = local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"); - libra::Vector<3> sun_dir_b = libra::Normalize(sun_pos_b); + libra::Vector<3> sun_dir_b = sun_pos_b.CalcNormalizedVector(); power_generation_W_ = cell_efficiency_ * transmission_efficiency_ * power_density * cell_area_m2_ * number_of_parallel_ * number_of_series_ * InnerProduct(normal_vector_, sun_dir_b); // TODO: Improve implementation. For example, update IV curve with sun direction and calculate generated power diff --git a/src/components/real/propulsion/simple_thruster.cpp b/src/components/real/propulsion/simple_thruster.cpp index b1227b573..c66ab1d81 100644 --- a/src/components/real/propulsion/simple_thruster.cpp +++ b/src/components/real/propulsion/simple_thruster.cpp @@ -44,7 +44,7 @@ SimpleThruster::~SimpleThruster() {} void SimpleThruster::Initialize(const double magnitude_standard_deviation_N, const double direction_standard_deviation_rad) { magnitude_random_noise_.SetParameters(0.0, magnitude_standard_deviation_N); direction_random_noise_.SetParameters(0.0, direction_standard_deviation_rad); - thrust_direction_b_ = Normalize(thrust_direction_b_); + thrust_direction_b_ = thrust_direction_b_.CalcNormalizedVector(); } void SimpleThruster::MainRoutine(const int time_count) { diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index c074d2358..80842cf80 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -23,15 +23,14 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction libra::Vector<3> force_b_N(0.0); libra::Vector<3> torque_b_Nm(0.0); - libra::Vector<3> input_b_normal(input_direction_b); - Normalize(input_b_normal); + libra::Vector<3> input_b_normal = input_direction_b.CalcNormalizedVector(); for (size_t i = 0; i < surfaces_.size(); i++) { if (cos_theta_[i] > 0.0) { // if the surface faces to the disturbance source (sun or air) // calc direction of in-plane force libra::Vector<3> normal = surfaces_[i].GetNormal_b(); libra::Vector<3> ncu = OuterProduct(input_b_normal, normal); - libra::Vector<3> ncu_normalized = Normalize(ncu); + libra::Vector<3> ncu_normalized = ncu.CalcNormalizedVector(); libra::Vector<3> in_plane_force_direction = OuterProduct(ncu_normalized, normal); // calc force libra::Vector<3> force_per_surface_b_N = -1.0 * normal_coefficients_[i] * normal + tangential_coefficients_[i] * in_plane_force_direction; @@ -46,8 +45,7 @@ libra::Vector<3> SurfaceForce::CalcTorqueForce(libra::Vector<3>& input_direction } void SurfaceForce::CalcTheta(libra::Vector<3>& input_direction_b) { - libra::Vector<3> input_b_normal(input_direction_b); - Normalize(input_b_normal); + libra::Vector<3> input_b_normal = input_direction_b.CalcNormalizedVector(); for (size_t i = 0; i < surfaces_.size(); i++) { cos_theta_[i] = InnerProduct(surfaces_[i].GetNormal_b(), input_b_normal); diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 23b061578..0ecf08c2e 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -42,8 +42,8 @@ void ControlledAttitude::Initialize(void) { return; } // pointing direction check - Normalize(main_target_direction_b_); - Normalize(sub_target_direction_b_); + main_target_direction_b_ = main_target_direction_b_.CalcNormalizedVector(); + sub_target_direction_b_ = sub_target_direction_b_.CalcNormalizedVector(); double tmp = InnerProduct(main_target_direction_b_, sub_target_direction_b_); tmp = std::abs(tmp); if (tmp > cos(kMinDirectionAngle_rad)) { @@ -86,7 +86,7 @@ libra::Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode m } else if (mode == ORBIT_NORMAL_POINTING) { direction = OuterProduct(orbit_->GetPosition_i_m(), orbit_->GetVelocity_i_m_s()); } - Normalize(direction); + direction = direction.CalcNormalizedVector(); return direction; } @@ -107,9 +107,9 @@ libra::Matrix<3, 3> ControlledAttitude::CalcDcm(const libra::Vector<3> main_dire ex = main_direction; libra::Vector<3> tmp1 = OuterProduct(ex, sub_direction); libra::Vector<3> tmp2 = OuterProduct(tmp1, ex); - ey = Normalize(tmp2); + ey = tmp2.CalcNormalizedVector(); libra::Vector<3> tmp3 = OuterProduct(ex, ey); - ez = Normalize(tmp3); + ez = tmp3.CalcNormalizedVector(); // Generate DCM libra::Matrix<3, 3> dcm; diff --git a/src/dynamics/orbit/orbit.cpp b/src/dynamics/orbit/orbit.cpp index f6054e5fe..5adb3aa63 100644 --- a/src/dynamics/orbit/orbit.cpp +++ b/src/dynamics/orbit/orbit.cpp @@ -6,12 +6,12 @@ libra::Quaternion Orbit::CalcQuaternion_i2lvlh() const { libra::Vector<3> lvlh_x = spacecraft_position_i_m_; // x-axis in LVLH frame is position vector direction from geocenter to satellite - libra::Vector<3> lvlh_ex = Normalize(lvlh_x); + libra::Vector<3> lvlh_ex = lvlh_x.CalcNormalizedVector(); libra::Vector<3> lvlh_z = OuterProduct(spacecraft_position_i_m_, spacecraft_velocity_i_m_s_); // z-axis in LVLH frame is angular momentum vector direction of orbit - libra::Vector<3> lvlh_ez = Normalize(lvlh_z); + libra::Vector<3> lvlh_ez = lvlh_z.CalcNormalizedVector(); libra::Vector<3> lvlh_y = OuterProduct(lvlh_z, lvlh_x); - libra::Vector<3> lvlh_ey = Normalize(lvlh_y); + libra::Vector<3> lvlh_ey = lvlh_y.CalcNormalizedVector(); libra::Matrix<3, 3> dcm_i2lvlh; dcm_i2lvlh[0][0] = lvlh_ex[0]; diff --git a/src/library/math/vector.cpp b/src/library/math/vector.cpp index 4df438a51..bd4f3501f 100644 --- a/src/library/math/vector.cpp +++ b/src/library/math/vector.cpp @@ -35,19 +35,19 @@ Vector<3, double> GenerateOrthogonalUnitVector(const Vector<3, double>& v) { orthogonal_vector[0] = 0.0; orthogonal_vector[1] = v[2]; orthogonal_vector[2] = -v[1]; - orthogonal_vector = Normalize(orthogonal_vector); + orthogonal_vector = orthogonal_vector.CalcNormalizedVector(); return (orthogonal_vector); } else if (v[1] * v[1] <= v[0] * v[0] && v[1] * v[1] <= v[2] * v[2]) { orthogonal_vector[0] = -v[2]; orthogonal_vector[1] = 0.0; orthogonal_vector[2] = v[0]; - orthogonal_vector = Normalize(orthogonal_vector); + orthogonal_vector = orthogonal_vector.CalcNormalizedVector(); return (orthogonal_vector); } else { orthogonal_vector[0] = v[1]; orthogonal_vector[1] = -v[0]; orthogonal_vector[2] = 0.0; - orthogonal_vector = Normalize(orthogonal_vector); + orthogonal_vector = orthogonal_vector.CalcNormalizedVector(); return (orthogonal_vector); } } diff --git a/src/library/math/vector.hpp b/src/library/math/vector.hpp index 2bca9f28e..5901c34c4 100644 --- a/src/library/math/vector.hpp +++ b/src/library/math/vector.hpp @@ -60,6 +60,15 @@ class Vector { */ double CalcNorm() const; + /** + * @fn CalcNormalizedVector + * @brief Normalize the target vector + * @note Warning: v is overwritten. + * @param [in/out] v: Target vector + * @return Normalized vector + */ + Vector CalcNormalizedVector() const; + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 1D-array using `[]` @@ -199,16 +208,6 @@ const T InnerProduct(const Vector& lhs, const Vector& rhs); template const Vector<3, T> OuterProduct(const Vector<3, T>& lhs, const Vector<3, T>& rhs); -/** - * @fn Normalize - * @brief Normalize the target vector - * @note Warning: v is overwritten. - * @param [in/out] v: Target vector - * @return Normalized vector - */ -template -Vector& Normalize(Vector& v); - /** * @fn CalcAngleTwoVectors_rad * @brief Calculate angle between two vectors diff --git a/src/library/math/vector_template_functions.hpp b/src/library/math/vector_template_functions.hpp index 48efcc57a..4706eab2a 100644 --- a/src/library/math/vector_template_functions.hpp +++ b/src/library/math/vector_template_functions.hpp @@ -122,19 +122,22 @@ double Vector::CalcNorm() const { return sqrt(temp); } -template -Vector& Normalize(Vector& v) { - double n = v.CalcNorm(); - if (n == 0.0) { - return v; - } +template +Vector Vector::CalcNormalizedVector() const { + Vector normalized; - n = 1.0 / n; for (size_t i = 0; i < N; ++i) { - v[i] *= n; + normalized[i] = (double)(this->vector_[i]); } - return v; + double n = normalized.CalcNorm(); + if (n == 0.0) { + return normalized; + } + + normalized /= n; + + return normalized; } template diff --git a/src/library/orbit/orbital_elements.cpp b/src/library/orbit/orbital_elements.cpp index 97a9abef3..db7bd24a3 100644 --- a/src/library/orbit/orbital_elements.cpp +++ b/src/library/orbit/orbital_elements.cpp @@ -43,8 +43,7 @@ void OrbitalElements::CalcOeFromPosVel(const double gravity_constant_m3_s2, cons semi_major_axis_m_ = gravity_constant_m3_s2 / (2.0 * gravity_constant_m3_s2 / r_m - v2_m2_s2); // inclination - libra::Vector<3> h_direction = h; - h_direction = Normalize(h_direction); + libra::Vector<3> h_direction = h.CalcNormalizedVector(); inclination_rad_ = acos(h_direction[2]); // RAAN diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index de8b5813b..185dfedf1 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -56,7 +56,7 @@ bool GroundStation::CalcIsVisible(const libra::Vector<3> spacecraft_position_ece libra::Quaternion q_ecef_to_ltc = geodetic_position_.GetQuaternionXcxfToLtc(); libra::Vector<3> sc_pos_ltc = q_ecef_to_ltc.FrameConversion(spacecraft_position_ecef_m - position_ecef_m_); // Satellite position in LTC frame [m] - Normalize(sc_pos_ltc); + sc_pos_ltc = sc_pos_ltc.CalcNormalizedVector(); libra::Vector<3> dir_gs_to_zenith = libra::Vector<3>(0); dir_gs_to_zenith[2] = 1; diff --git a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp index 70cbab799..aee94d3b7 100644 --- a/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp +++ b/src/simulation/monte_carlo_simulation/initialize_monte_carlo_parameters.cpp @@ -205,7 +205,7 @@ void InitializedMonteCarloParameters::CalcSphericalNormalNormal(libra::Vector<3> // An unit vector perpendicular with the mean vector // In case of the mean vector is parallel with X or Y axis, selecting the axis depend on the norm of outer product - libra::Vector<3> normal_unit_vec = op_x.CalcNorm() > op_y.CalcNorm() ? Normalize(op_x) : Normalize(op_y); + libra::Vector<3> normal_unit_vec = op_x.CalcNorm() > op_y.CalcNorm() ? op_x = op_x.CalcNormalizedVector() : op_y = op_y.CalcNormalizedVector(); double rotation_angle_of_normal_unit_vec = InitializedMonteCarloParameters::Generate1dUniform(0.0, libra::tau); libra::Quaternion rotation_of_normal_unit_vec(mean_vec_dir, diff --git a/src/simulation/spacecraft/structure/initialize_structure.cpp b/src/simulation/spacecraft/structure/initialize_structure.cpp index 44ea055b4..3ad332234 100644 --- a/src/simulation/spacecraft/structure/initialize_structure.cpp +++ b/src/simulation/spacecraft/structure/initialize_structure.cpp @@ -97,7 +97,7 @@ std::vector InitSurfaces(std::string file_name) { { cout << "Surface Warning! " << keyword << ": norm is larger than 1.0."; cout << "The vector is normalized.\n"; - normal = Normalize(normal); + normal = normal.CalcNormalizedVector(); } // Add a surface diff --git a/src/simulation/spacecraft/structure/surface.hpp b/src/simulation/spacecraft/structure/surface.hpp index a2837cfa1..ad93c3b0d 100644 --- a/src/simulation/spacecraft/structure/surface.hpp +++ b/src/simulation/spacecraft/structure/surface.hpp @@ -70,10 +70,7 @@ class Surface { * @brief Set normal vector of the surface in body frame * @param[in] normal_b: Normal vector of the surface in body frame */ - inline void SetNormal_b(const libra::Vector<3> normal_b) { - normal_b_ = normal_b; - normal_b_ = Normalize(normal_b_); - } + inline void SetNormal_b(const libra::Vector<3> normal_b) { normal_b_ = normal_b.CalcNormalizedVector(); } /** * @fn SetArea_m2 * @brief Set area of the surface From abc631249dac83272826352711b6da095337bfd5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 12:53:10 +0100 Subject: [PATCH 1002/1086] Move Matrix::FillUp to member function --- src/library/math/matrix.hpp | 16 +++++++--------- src/library/math/matrix_template_functions.hpp | 6 +++--- 2 files changed, 10 insertions(+), 12 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 5e32b985a..a07d8c3d1 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -46,6 +46,13 @@ class Matrix { */ inline size_t GetColumnLength() const { return C; } + /** + * @fn FillUp + * @brief Fill up all elements with same value + * @param [in] t: Scalar value to fill up + */ + void FillUp(const T& t); + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 2D-array using `[]` @@ -139,15 +146,6 @@ class Matrix { inline bool IsValidRange(size_t row, size_t column) { return (row < R && column < C); } }; -/** - * @fn FillUp - * @brief Fill up all elements with same value - * @param [in] m: Target matrix - * @param [in] t: Scalar value to fill up - */ -template -void FillUp(Matrix& m, const T& t); - /** * @fn CalcTrace * @brief Calculate and return the trace of matrix diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 089f135c3..d925cba1f 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -56,10 +56,10 @@ const Matrix& Matrix::operator-=(const Matrix& m) { } template -void FillUp(Matrix& m, const T& t) { +void Matrix::FillUp(const T& t) { for (size_t i = 0; i < R; ++i) { for (size_t j = 0; j < C; ++j) { - m[i][j] = t; + matrix_[i][j] = t; } } } @@ -143,7 +143,7 @@ const Matrix Transpose(const Matrix& m) { template Matrix& Unitalize(Matrix& m) { - FillUp(m, 0.0); + m.FillUp(0.0); for (size_t i = 0; i < R; ++i) { m[i][i] = 1.0; } From 7df1e85a6008b26348eb47efe9c17ac39d601cdb Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 12:57:07 +0100 Subject: [PATCH 1003/1086] Move Matrix::CalcTrace to member function --- src/library/math/matrix.hpp | 16 +++++++--------- src/library/math/matrix_template_functions.hpp | 11 +++++++---- 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index a07d8c3d1..88af4e570 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -53,6 +53,13 @@ class Matrix { */ void FillUp(const T& t); + /** + * @fn CalcTrace + * @brief Calculate and return the trace of matrix + * @return Trace of the matrix + */ + T CalcTrace() const; + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 2D-array using `[]` @@ -146,15 +153,6 @@ class Matrix { inline bool IsValidRange(size_t row, size_t column) { return (row < R && column < C); } }; -/** - * @fn CalcTrace - * @brief Calculate and return the trace of matrix - * @param [in] m: Target matrix - * @return Trace of the matrix - */ -template -T CalcTrace(const Matrix& m); - /** * @fn print * @brief Generate all elements to outstream diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index d925cba1f..dbefc6dbb 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -64,11 +64,14 @@ void Matrix::FillUp(const T& t) { } } -template -T CalcTrace(const Matrix& m) { +template +T Matrix::CalcTrace() const { T trace = 0.0; - for (size_t i = 0; i < N; ++i) { - trace += m[i][i]; + + if (R != C) return trace; + + for (size_t i = 0; i < R; ++i) { + trace += matrix_[i][i]; } return trace; } From 7b6a19f2d78f15f4d605d9bb7040fbc71c68120f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 12:59:56 +0100 Subject: [PATCH 1004/1086] Move Matrix::Print to member function --- src/library/math/matrix.hpp | 18 ++++++++---------- src/library/math/matrix_template_functions.hpp | 6 +++--- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 88af4e570..d10fc164a 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -60,6 +60,14 @@ class Matrix { */ T CalcTrace() const; + /** + * @fn Print + * @brief Generate all elements to outstream + * @param [in] delimiter: Delimiter (Default: tab) + * @param [out] stream: Output target(Default: cout) + */ + void Print(char delimiter = '\t', std::ostream& stream = std::cout); + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 2D-array using `[]` @@ -153,16 +161,6 @@ class Matrix { inline bool IsValidRange(size_t row, size_t column) { return (row < R && column < C); } }; -/** - * @fn print - * @brief Generate all elements to outstream - * @param [in] m: Target matrix - * @param [in] delimiter: Delimiter (Default: tab) - * @param [out] stream: Output target(Default: cout) - */ -template -void Print(const Matrix& m, char delimiter = '\t', std::ostream& stream = std::cout); - /** * @fn operator + * @brief Add two matrices diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index dbefc6dbb..64eb3a0d4 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -77,11 +77,11 @@ T Matrix::CalcTrace() const { } template -void Print(const Matrix& m, char delimiter, std::ostream& stream) { +void Matrix::Print(char delimiter, std::ostream& stream) { for (size_t i = 0; i < R; ++i) { - stream << m[i][0]; + stream << matrix_[i][0]; for (size_t j = 1; j < C; ++j) { - stream << delimiter << m[i][j]; + stream << delimiter << matrix_[i][j]; } stream << std::endl; } From daad88d22cd7652bd9632cc98e87fbc7b5aa592a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 13:10:07 +0100 Subject: [PATCH 1005/1086] Move Matrix::Transpose to member function --- src/disturbances/geopotential.cpp | 2 +- src/dynamics/attitude/controlled_attitude.cpp | 2 +- src/library/math/matrix.hpp | 16 +++++++--------- src/library/math/matrix_template_functions.hpp | 4 ++-- src/simulation/ground_station/ground_station.cpp | 2 +- 5 files changed, 12 insertions(+), 14 deletions(-) diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 99ac8c41c..db616da40 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -79,7 +79,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam #endif libra::Matrix<3, 3> trans_eci2ecef_ = local_environment.GetCelestialInformation().GetGlobalInformation().GetEarthRotation().GetDcmJ2000ToXcxf(); - libra::Matrix<3, 3> trans_ecef2eci = Transpose(trans_eci2ecef_); + libra::Matrix<3, 3> trans_ecef2eci = trans_eci2ecef_.Transpose(); acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 0ecf08c2e..7a7b1092e 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -96,7 +96,7 @@ void ControlledAttitude::PointingControl(const libra::Vector<3> main_direction_i // Calc DCM Target->body libra::Matrix<3, 3> dcm_t2b = CalcDcm(main_target_direction_b_, sub_target_direction_b_); // Calc DCM ECI->body - libra::Matrix<3, 3> dcm_i2b = dcm_t2b * Transpose(dcm_t2i); + libra::Matrix<3, 3> dcm_i2b = dcm_t2b * dcm_t2i.Transpose(); // Convert to Quaternion quaternion_i2b_ = libra::Quaternion::ConvertFromDcm(dcm_i2b); } diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index d10fc164a..c3ecc9577 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -68,6 +68,13 @@ class Matrix { */ void Print(char delimiter = '\t', std::ostream& stream = std::cout); + /** + * @fn Transpose + * @brief Calculate and return transposed matrix + * @return Result of transposed matrix + */ + const Matrix Transpose() const; + /** * @fn Cast operator to directly access the elements * @brief Operator to access the elements similar with the 2D-array using `[]` @@ -201,15 +208,6 @@ const Matrix operator*(const T& lhs, const Matrix& rhs); template const Matrix operator*(const Matrix& lhs, const Matrix& rhs); -/** - * @fn Transpose - * @brief Calculate and return transposed matrix - * @param [in] m: Target matrix - * @return Result of transposed matrix - */ -template -const Matrix Transpose(const Matrix& m); - /** * @fn Unitalize * @brief Rewrite the input matrix as the identity matrix diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 64eb3a0d4..960a7f4e5 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -134,11 +134,11 @@ const Matrix operator*(const Matrix& lhs, const Matrix -const Matrix Transpose(const Matrix& m) { +const Matrix Matrix::Transpose() const { Matrix temp; for (size_t i = 0; i < R; ++i) { for (size_t j = 0; j < C; ++j) { - temp[j][i] = m[i][j]; + temp[j][i] = matrix_[i][j]; } } return temp; diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 185dfedf1..c9383916c 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -46,7 +46,7 @@ void GroundStation::Initialize(const SimulationConfiguration* configuration, con void GroundStation::LogSetup(Logger& logger) { logger.AddLogList(this); } void GroundStation::Update(const CelestialRotation& celestial_rotation, const Spacecraft& spacecraft) { - libra::Matrix<3, 3> dcm_ecef2eci = Transpose(celestial_rotation.GetDcmJ2000ToXcxf()); + libra::Matrix<3, 3> dcm_ecef2eci = celestial_rotation.GetDcmJ2000ToXcxf().Transpose(); position_i_m_ = dcm_ecef2eci * position_ecef_m_; is_visible_[spacecraft.GetSpacecraftId()] = CalcIsVisible(spacecraft.GetDynamics().GetOrbit().GetPosition_ecef_m()); From 4786f3f497dab2cbc67e1f9bce0b3d8818de3296 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 13:25:30 +0100 Subject: [PATCH 1006/1086] Delete Unitalize function and change to use MakeIdentityMatrix --- src/environment/global/celestial_rotation.cpp | 6 ++--- src/library/math/matrix.hpp | 10 -------- .../math/matrix_template_functions.hpp | 23 +++++++------------ 3 files changed, 11 insertions(+), 28 deletions(-) diff --git a/src/environment/global/celestial_rotation.cpp b/src/environment/global/celestial_rotation.cpp index d2bf28445..abca8a573 100644 --- a/src/environment/global/celestial_rotation.cpp +++ b/src/environment/global/celestial_rotation.cpp @@ -20,7 +20,7 @@ CelestialRotation::CelestialRotation(const RotationMode rotation_mode, const std::string center_body_name) { planet_name_ = "Anonymous"; rotation_mode_ = Idle; - Unitalize(dcm_j2000_to_xcxf_); + dcm_j2000_to_xcxf_ = libra::MakeIdentityMatrix<3>(); dcm_teme_to_xcxf_ = dcm_j2000_to_xcxf_; if (center_body_name == "EARTH") { InitCelestialRotationAsEarth(rotation_mode, center_body_name); @@ -115,12 +115,12 @@ void CelestialRotation::InitCelestialRotationAsEarth(const RotationMode rotation } else { // If the rotation mode is neither Simple nor Full, disable the rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - Unitalize(dcm_j2000_to_xcxf_); + dcm_j2000_to_xcxf_ = libra::MakeIdentityMatrix<3>(); } } else { // If the center object is not the Earth, disable the Earth's rotation calculation and make the DCM a unit matrix rotation_mode_ = Idle; - Unitalize(dcm_j2000_to_xcxf_); + dcm_j2000_to_xcxf_ = libra::MakeIdentityMatrix<3>(); } } diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index c3ecc9577..3f4ed9ab8 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -208,16 +208,6 @@ const Matrix operator*(const T& lhs, const Matrix& rhs); template const Matrix operator*(const Matrix& lhs, const Matrix& rhs); -/** - * @fn Unitalize - * @brief Rewrite the input matrix as the identity matrix - * @note Warning: m is overwritten. - * @param [in/out] m: Target matrix - * @return The identity matrix - */ -template -Matrix& Unitalize(Matrix& m); - /** * @fn MakeIdentityMatrix * @brief Generate identity matrix diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 960a7f4e5..0a3b9c5bd 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -145,25 +145,18 @@ const Matrix Matrix::Transpose() const { } template -Matrix& Unitalize(Matrix& m) { - m.FillUp(0.0); +Matrix MakeIdentityMatrix() { + Matrix m(0.0); for (size_t i = 0; i < R; ++i) { m[i][i] = 1.0; } return m; } -template -Matrix MakeIdentityMatrix() { - Matrix m; - Unitalize(m); - return m; -} - template Matrix MakeRotationMatrixX(const double& theta_rad) { - Matrix m; - Unitalize(m); + Matrix m = MakeIdentityMatrix(); + m[1][1] = cos(theta_rad); m[1][2] = sin(theta_rad); m[2][1] = -sin(theta_rad); @@ -173,8 +166,8 @@ Matrix MakeRotationMatrixX(const double& theta_rad) { template Matrix MakeRotationMatrixY(const double& theta_rad) { - Matrix m; - Unitalize(m); + Matrix m = MakeIdentityMatrix(); + m[0][0] = cos(theta_rad); m[0][2] = -sin(theta_rad); m[2][0] = sin(theta_rad); @@ -184,8 +177,8 @@ Matrix MakeRotationMatrixY(const double& theta_rad) { template Matrix MakeRotationMatrixZ(const double& theta_rad) { - Matrix m; - Unitalize(m); + Matrix m = MakeIdentityMatrix(); + m[0][0] = cos(theta_rad); m[0][1] = sin(theta_rad); m[1][0] = -sin(theta_rad); From b5ab1362e8dbe72a38cdcfdd54d3211d73e79b9d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 13:28:21 +0100 Subject: [PATCH 1007/1086] Add description --- src/library/math/matrix.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index 3f4ed9ab8..b79516db4 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -57,6 +57,7 @@ class Matrix { * @fn CalcTrace * @brief Calculate and return the trace of matrix * @return Trace of the matrix + * @note When the matrix is not a square matrix, 0.0 is returned */ T CalcTrace() const; From f168fb0283ef0737a574f2e34d2f5818e32cac76 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 7 Mar 2023 13:29:02 +0100 Subject: [PATCH 1008/1086] Add const for Print function --- src/library/math/matrix.hpp | 2 +- src/library/math/matrix_template_functions.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/library/math/matrix.hpp b/src/library/math/matrix.hpp index b79516db4..4b9f6b91f 100644 --- a/src/library/math/matrix.hpp +++ b/src/library/math/matrix.hpp @@ -67,7 +67,7 @@ class Matrix { * @param [in] delimiter: Delimiter (Default: tab) * @param [out] stream: Output target(Default: cout) */ - void Print(char delimiter = '\t', std::ostream& stream = std::cout); + void Print(char delimiter = '\t', std::ostream& stream = std::cout) const; /** * @fn Transpose diff --git a/src/library/math/matrix_template_functions.hpp b/src/library/math/matrix_template_functions.hpp index 0a3b9c5bd..a31c74a35 100644 --- a/src/library/math/matrix_template_functions.hpp +++ b/src/library/math/matrix_template_functions.hpp @@ -77,7 +77,7 @@ T Matrix::CalcTrace() const { } template -void Matrix::Print(char delimiter, std::ostream& stream) { +void Matrix::Print(char delimiter, std::ostream& stream) const { for (size_t i = 0; i < R; ++i) { stream << matrix_[i][0]; for (size_t j = 1; j < C; ++j) { From 749f86cb73537021b16755052a1d1e1ed4a0e721 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 12 Mar 2023 08:00:58 +0100 Subject: [PATCH 1009/1086] Fix reg -> register --- src/components/real/cdh/on_board_computer.cpp | 8 ++++---- src/components/real/cdh/on_board_computer.hpp | 8 ++++---- .../real/cdh/on_board_computer_with_c2a.cpp | 10 +++++----- .../real/cdh/on_board_computer_with_c2a.hpp | 8 ++++---- src/simulation/hils/hils_port_manager.cpp | 13 +++++++------ src/simulation/hils/hils_port_manager.hpp | 11 ++++++----- 6 files changed, 30 insertions(+), 28 deletions(-) diff --git a/src/components/real/cdh/on_board_computer.cpp b/src/components/real/cdh/on_board_computer.cpp index 652739919..ad23fadf4 100644 --- a/src/components/real/cdh/on_board_computer.cpp +++ b/src/components/real/cdh/on_board_computer.cpp @@ -90,19 +90,19 @@ int OnBoardComputer::I2cCloseComPort(int port_id) { return 0; } -int OnBoardComputer::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, +int OnBoardComputer::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < length; i++) { - i2c_port->WriteRegister(i2c_address, reg_address, data[i]); + i2c_port->WriteRegister(i2c_address, register_address, data[i]); } return 0; } -int OnBoardComputer::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, +int OnBoardComputer::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_ports_[port_id]; for (int i = 0; i < length; i++) { - data[i] = i2c_port->ReadRegister(reg_address, i2c_address); + data[i] = i2c_port->ReadRegister(register_address, i2c_address); } return 0; } diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index dd85e61a3..a56f37715 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -132,24 +132,24 @@ class OnBoardComputer : public Component { * @brief Write value in the target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device - * @param [in] reg_address: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [in] data: Write data buffer * @param [in] length: Length of data * @return 0 */ - virtual int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + virtual int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, const unsigned char* data, const unsigned char length); /** * @fn I2cComponentReadRegister * @brief Read value in the target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device - * @param [in] reg_address: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [out] data: Write data buffer * @param [in] length: Length of data * @return 0 */ - virtual int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + virtual int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, unsigned char* data, const unsigned char length); /** * @fn I2cComponentReadCommand diff --git a/src/components/real/cdh/on_board_computer_with_c2a.cpp b/src/components/real/cdh/on_board_computer_with_c2a.cpp index 45a11dd86..340435309 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.cpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.cpp @@ -171,19 +171,19 @@ int ObcWithC2a::I2cReadRegister(int port_id, const unsigned char i2c_address, un return 0; } -int ObcWithC2a::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, - const unsigned char length) { +int ObcWithC2a::I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, + const unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < length; i++) { - i2c_port->WriteRegister(i2c_address, reg_address + i, data[i]); + i2c_port->WriteRegister(i2c_address, register_address + i, data[i]); } return 0; } -int ObcWithC2a::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, +int ObcWithC2a::I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, unsigned char* data, const unsigned char length) { I2cPort* i2c_port = i2c_com_ports_c2a_[port_id]; for (unsigned char i = 0; i < length; i++) { - data[i] = i2c_port->ReadRegister(i2c_address, reg_address + i); + data[i] = i2c_port->ReadRegister(i2c_address, register_address + i); } return 0; } diff --git a/src/components/real/cdh/on_board_computer_with_c2a.hpp b/src/components/real/cdh/on_board_computer_with_c2a.hpp index 9f8b73b82..94f7cd317 100644 --- a/src/components/real/cdh/on_board_computer_with_c2a.hpp +++ b/src/components/real/cdh/on_board_computer_with_c2a.hpp @@ -148,24 +148,24 @@ class ObcWithC2a : public OnBoardComputer { * @brief Write value in the target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device - * @param [in] reg_address: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [in] data: Write data buffer * @param [in] length: Length of data * @return 0 */ - int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, const unsigned char* data, + int I2cComponentWriteRegister(int port_id, const unsigned char i2c_address, const unsigned char rregister_address, const unsigned char* data, const unsigned char length) override; /** * @fn I2cComponentReadRegister * @brief Read value in the target device's register * @param [in] port_id: Port ID * @param [in] i2c_address: I2C address of the target device - * @param [in] reg_address: Register address of the target device + * @param [in] register_address: Register address of the target device * @param [out] data: Write data buffer * @param [in] length: Length of data * @return 0 */ - int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char reg_address, unsigned char* data, + int I2cComponentReadRegister(int port_id, const unsigned char i2c_address, const unsigned char register_address, unsigned char* data, const unsigned char length) override; /** * @fn I2cComponentReadCommand diff --git a/src/simulation/hils/hils_port_manager.cpp b/src/simulation/hils/hils_port_manager.cpp index a70902bcb..3e7e65264 100644 --- a/src/simulation/hils/hils_port_manager.cpp +++ b/src/simulation/hils/hils_port_manager.cpp @@ -141,18 +141,18 @@ int HilsPortManager::I2cTargetCloseComPort(unsigned int port_id) { #endif } -int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, +int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned char register_address, const unsigned char* data, const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < length; i++) { - port->WriteRegister(reg_address + i, data[i]); + port->WriteRegister(register_address + i, data[i]); } return 0; #else UNUSED(port_id); - UNUSED(reg_address); + UNUSED(register_address); UNUSED(data); UNUSED(length); @@ -160,17 +160,18 @@ int HilsPortManager::I2cTargetWriteRegister(unsigned int port_id, const unsigned #endif } -int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length) { +int HilsPortManager::I2cTargetReadRegister(unsigned int port_id, const unsigned char register_address, unsigned char* data, + const unsigned char length) { #ifdef USE_HILS HilsI2cTargetPort* port = i2c_ports_[port_id]; if (port == nullptr) return -1; for (unsigned char i = 0; i < length; i++) { - data[i] = port->ReadRegister(reg_address + i); + data[i] = port->ReadRegister(register_address + i); } return 0; #else UNUSED(port_id); - UNUSED(reg_address); + UNUSED(register_address); UNUSED(data); UNUSED(length); diff --git a/src/simulation/hils/hils_port_manager.hpp b/src/simulation/hils/hils_port_manager.hpp index ebbade3b9..978a1a7bc 100644 --- a/src/simulation/hils/hils_port_manager.hpp +++ b/src/simulation/hils/hils_port_manager.hpp @@ -81,20 +81,21 @@ class HilsPortManager { * @fn I2cTargetReadRegister * @brief Read I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_address: Register address to read + * @param [in] register_address: Register address to read * @param [out] data: Data buffer to store the read data * @param [in] length: Read data length */ - virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char reg_address, unsigned char* data, const unsigned char length); + virtual int I2cTargetReadRegister(unsigned int port_id, const unsigned char register_address, unsigned char* data, const unsigned char length); /** - * @fn I2cTargetWriteRegister + * @brief * @brief Write data to I2C register in S2E * @param [in] port_id: COM port ID - * @param [in] reg_address: Register address to write + * @param [in] register_address: Register address to write * @param [in] data: Data to write * @param [in] length: Write data length */ - virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char reg_address, const unsigned char* data, const unsigned char length); + virtual int I2cTargetWriteRegister(unsigned int port_id, const unsigned char register_address, const unsigned char* data, + const unsigned char length); /** * @fn I2cTargetReadCommand * @brief Read I2C command buffer in S2E From 2c1509704868c3424a9297bf43987baf5a7e6a07 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 12 Mar 2023 08:14:01 +0100 Subject: [PATCH 1010/1086] Fix typos --- src/components/ideal/torque_generator.hpp | 4 ++-- src/components/real/aocs/initialize_magnetorquer.cpp | 12 ++++++------ 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index e7fc46cd6..db75006ad 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -68,10 +68,10 @@ class TorqueGenerator : public Component, public ILoggable { // Setter /** - * @fn SetTorque_b_Nm_Nm + * @fn SetTorque_b_Nm * @brief Set ordered torque in the body fixed frame [Nm] */ - inline void SetTorque_b_Nm_Nm(const libra::Vector<3> torque_b_Nm) { ordered_torque_b_Nm_ = torque_b_Nm; }; + inline void SetTorque_b_Nm(const libra::Vector<3> torque_b_Nm) { ordered_torque_b_Nm_ = torque_b_Nm; }; protected: libra::Vector<3> ordered_torque_b_Nm_{0.0}; //!< Ordered torque in the body fixed frame [Nm] diff --git a/src/components/real/aocs/initialize_magnetorquer.cpp b/src/components/real/aocs/initialize_magnetorquer.cpp index c203d0135..b446edfc1 100644 --- a/src/components/real/aocs/initialize_magnetorquer.cpp +++ b/src/components/real/aocs/initialize_magnetorquer.cpp @@ -34,8 +34,8 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, libra::Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - libra::Vector bias_noise_c_Am2_; - magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); + libra::Vector bias_noise_c_Am2; + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2); double random_walk_step_width_s = component_step_time_s * (double)prescaler; libra::Vector random_walk_standard_deviation_c_Am2; @@ -46,7 +46,7 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, int actuator_id, magtorquer_conf.ReadVector(MTSection, "white_noise_standard_deviation_c_Am2", normal_random_standard_deviation_c_Am2); Magnetorquer magtorquer(prescaler, clock_generator, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, min_magnetic_moment_c_Am2, - bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, + bias_noise_c_Am2, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } @@ -79,8 +79,8 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_ libra::Vector min_magnetic_moment_c_Am2; magtorquer_conf.ReadVector(MTSection, "min_output_magnetic_moment_c_Am2", min_magnetic_moment_c_Am2); - libra::Vector bias_noise_c_Am2_; - magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2_); + libra::Vector bias_noise_c_Am2; + magtorquer_conf.ReadVector(MTSection, "constant_bias_noise_c_Am2", bias_noise_c_Am2); double random_walk_step_width_s = component_step_time_s * (double)prescaler; libra::Vector random_walk_standard_deviation_c_Am2; @@ -94,7 +94,7 @@ Magnetorquer InitMagnetorquer(ClockGenerator* clock_generator, PowerPort* power_ power_port->InitializeWithInitializeFile(file_name); Magnetorquer magtorquer(prescaler, clock_generator, power_port, actuator_id, quaternion_b2c, scale_factor, max_magnetic_moment_c_Am2, - min_magnetic_moment_c_Am2, bias_noise_c_Am2_, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, + min_magnetic_moment_c_Am2, bias_noise_c_Am2, random_walk_step_width_s, random_walk_standard_deviation_c_Am2, random_walk_limit_c_Am2, normal_random_standard_deviation_c_Am2, geomagnetic_field); return magtorquer; } From 36def601486d8906c6233a248c08a3cee1acbdc0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 12 Mar 2023 08:17:38 +0100 Subject: [PATCH 1011/1086] Fix typo --- src/simulation/case/sample_case.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 6a6fa6acd..bde34effc 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -52,7 +52,7 @@ void SampleCase::Main() { // Debug output if (global_environment_->GetSimulationTime().GetState().disp_output) { - cout << "Progresss: " << global_environment_->GetSimulationTime().GetProgressionRate() << "%\r"; + cout << "Progress: " << global_environment_->GetSimulationTime().GetProgressionRate() << "%\r"; } } } From e00a42b6f9c8f063946d6a5105559c9deec48e41 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 11:42:26 +0100 Subject: [PATCH 1012/1086] Fix comments --- src/disturbances/disturbance.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 25c26ba3c..8dce88566 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -27,22 +27,22 @@ class Disturbance { } /** - * @fn GetTorque + * @fn GetTorque_b_Nm * @brief Return the disturbance torque in the body frame [Nm] */ virtual inline libra::Vector<3> GetTorque_b_Nm() { return torque_b_Nm_; } /** - * @fn GetTorque + * @fn GetForce_b_N * @brief Return the disturbance force in the body frame [N] */ virtual inline libra::Vector<3> GetForce_b_N() { return force_b_N_; } /** - * @fn GetTorque + * @fn GetAcceleration_b_m_s2 * @brief Return the disturbance acceleration in the body frame [m/s2] */ virtual inline libra::Vector<3> GetAcceleration_b_m_s2() { return acceleration_b_m_s2_; } /** - * @fn GetTorque + * @fn GetAcceleration_i_m_s2 * @brief Return the disturbance acceleration in the inertial frame [m/s2] */ virtual inline libra::Vector<3> GetAcceleration_i_m_s2() { return acceleration_i_m_s2_; } From 09d97f9028ec72f8a38e81e9e9c1dfc785c4b591 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 12:46:08 +0100 Subject: [PATCH 1013/1086] Add attitud dependent flag --- src/disturbances/disturbance.hpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 8dce88566..0e33fd076 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -19,7 +19,8 @@ class Disturbance { * @brief Constructor * @param [in] is_calculation_enabled: Calculation flag */ - Disturbance(const bool is_calculation_enabled = true) : is_calculation_enabled_(is_calculation_enabled) { + Disturbance(const bool is_calculation_enabled = true, const bool is_attitude_dependent = true) + : is_calculation_enabled_(is_calculation_enabled), is_attitude_dependent_(is_attitude_dependent) { force_b_N_ = libra::Vector<3>(0.0); torque_b_Nm_ = libra::Vector<3>(0.0); acceleration_b_m_s2_ = libra::Vector<3>(0.0); @@ -46,9 +47,15 @@ class Disturbance { * @brief Return the disturbance acceleration in the inertial frame [m/s2] */ virtual inline libra::Vector<3> GetAcceleration_i_m_s2() { return acceleration_i_m_s2_; } + /** + * @fn GetAcceleration_i_m_s2 + * @brief Return the attitude dependent flag + */ + virtual inline bool IsAttitudeDependent() { return is_attitude_dependent_; } protected: bool is_calculation_enabled_; //!< Flag to calculate the disturbance + bool is_attitude_dependent_; //!< Flag to show the disturbance depends on attitude information libra::Vector<3> force_b_N_; //!< Disturbance force in the body frame [N] libra::Vector<3> torque_b_Nm_; //!< Disturbance torque in the body frame [Nm] libra::Vector<3> acceleration_b_m_s2_; //!< Disturbance acceleration in the body frame [m/s2] From 1ba7c7ab27793542c542e4af4b364d91f56cd87a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 12:48:24 +0100 Subject: [PATCH 1014/1086] Add Update function --- src/disturbances/disturbance.hpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 0e33fd076..25122d05e 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -27,6 +27,27 @@ class Disturbance { acceleration_b_m_s2_ = libra::Vector<3>(0.0); } + /** + * @fn UpdateIfEnabled + * @brief Update calculated disturbance when the calculation flag is true + */ + virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { + if (is_calculation_enabled_) { + Update(local_environment, dynamics); + } else { + force_b_N_ *= 0.0; + torque_b_Nm_ *= 0.0; + acceleration_b_m_s2_ *= 0.0; + acceleration_i_m_s2_ *= 0.0; + } + } + + /** + * @fn Update + * @brief Pure virtual function to define the disturbance calculation + */ + virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; + /** * @fn GetTorque_b_Nm * @brief Return the disturbance torque in the body frame [Nm] From b3c050e225710e8ec6431423fadc48ba0423d32e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 12:49:39 +0100 Subject: [PATCH 1015/1086] Delete simple and acceleration disturbance --- src/disturbances/acceleration_disturbance.hpp | 51 ---------------- src/disturbances/simple_disturbance.hpp | 58 ------------------- 2 files changed, 109 deletions(-) delete mode 100644 src/disturbances/acceleration_disturbance.hpp delete mode 100644 src/disturbances/simple_disturbance.hpp diff --git a/src/disturbances/acceleration_disturbance.hpp b/src/disturbances/acceleration_disturbance.hpp deleted file mode 100644 index f9803e129..000000000 --- a/src/disturbances/acceleration_disturbance.hpp +++ /dev/null @@ -1,51 +0,0 @@ -/** - * @file acceleration_disturbance.hpp - * @brief Abstract class for a disturbance which generate acceleration only (not force) - */ - -#ifndef S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ -#define S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ - -#include "../dynamics/dynamics.hpp" -#include "../environment/local/local_environment.hpp" -#include "disturbance.hpp" - -/** - * @class AccelerationDisturbance - * @brief Abstract class for a disturbance which generate acceleration only (not force) - */ -class AccelerationDisturbance : public Disturbance, public ILoggable { - public: - /** - * @fn AccelerationDisturbance - * @brief Constructor - * @param [in] is_calculation_enabled: Calculation flag - */ - AccelerationDisturbance(const bool is_calculation_enabled = true) : Disturbance(is_calculation_enabled) {} - /** - * @fn ~AccelerationDisturbance - * @brief Destructor - */ - virtual ~AccelerationDisturbance() {} - - /** - * @fn UpdateIfEnabled - * @brief Update calculated disturbance when the calculation flag is true - */ - virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - if (is_calculation_enabled_) { - Update(local_environment, dynamics); - } else { - acceleration_b_m_s2_ *= 0.0; - acceleration_i_m_s2_ *= 0.0; - } - } - - /** - * @fn Update - * @brief Pure virtual function to define the disturbance calculation - */ - virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; -}; - -#endif // S2E_DISTURBANCES_ACCELERATION_DISTURBANCE_HPP_ diff --git a/src/disturbances/simple_disturbance.hpp b/src/disturbances/simple_disturbance.hpp deleted file mode 100644 index 6d8e0ffa2..000000000 --- a/src/disturbances/simple_disturbance.hpp +++ /dev/null @@ -1,58 +0,0 @@ -/** - * @file simple_disturbance.hpp - * @brief Abstract class for a disturbance - * @note It is better to use this abstract class for all disturbances, but it is difficult. (e.g. Gravity between spacecraft.) - * In the difficult case, users need to use the Disturbance class directory. - */ - -#ifndef S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ -#define S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ - -#include "../dynamics/dynamics.hpp" -#include "../environment/local/local_environment.hpp" -#include "disturbance.hpp" - -/** - * @class SimpleDisturbance - * @brief Abstract class for a disturbance - */ -class SimpleDisturbance : public Disturbance, public ILoggable { - public: - /** - * @fn SimpleDisturbance - * @brief Constructor - * @param [in] is_calculation_enabled: Calculation flag - */ - SimpleDisturbance(const bool is_calculation_enabled = true) : Disturbance(is_calculation_enabled) {} - - /** - * @fn ~SimpleDisturbance - * @brief Destructor - */ - virtual ~SimpleDisturbance() {} - - /** - * @fn UpdateIfEnabled - * @brief Update calculated disturbance when the calculation flag is true - * @param [in] local_environment: Local environment information - * @param [in] dynamics: Dynamics information - */ - virtual inline void UpdateIfEnabled(const LocalEnvironment& local_environment, const Dynamics& dynamics) { - if (is_calculation_enabled_) { - Update(local_environment, dynamics); - } else { - force_b_N_ *= 0.0; - torque_b_Nm_ *= 0.0; - } - } - - /** - * @fn Update - * @brief Pure virtual function to define the disturbance calculation - * @param [in] local_environment: Local environment information - * @param [in] dynamics: Dynamics information - */ - virtual void Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) = 0; -}; - -#endif // S2E_DISTURBANCES_SIMPLE_DISTURBANCE_HPP_ From a5561e470ca8234cad04e950277a7330831a107e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 13:07:47 +0100 Subject: [PATCH 1016/1086] Rename GeoPotential to Geopotential --- src/disturbances/disturbances.cpp | 2 +- src/disturbances/geopotential.cpp | 22 ++++++++++---------- src/disturbances/geopotential.hpp | 8 +++---- src/disturbances/gravity_gradient.hpp | 4 ++-- src/disturbances/initialize_disturbances.cpp | 4 ++-- src/disturbances/initialize_disturbances.hpp | 4 ++-- 6 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index b5493d989..bce073cd8 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -88,7 +88,7 @@ void Disturbances::InitializeInstances(const SimulationConfiguration* simulation MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetResidualMagneticMoment())); disturbances_list_.push_back(mag_dist); - GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); + Geopotential* geopotential = new Geopotential(InitGeoPotential(initialize_file_name_)); acceleration_disturbances_list_.push_back(geopotential); } diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 99ac8c41c..19f35b3b5 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -15,7 +15,7 @@ // #define DEBUG_GEOPOTENTIAL -GeoPotential::GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled) +Geopotential::Geopotential(const int degree, const std::string file_path, const bool is_calculation_enabled) : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { // Initialize acceleration_ecef_m_s2_ = libra::Vector<3>(0.0); @@ -23,9 +23,9 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const // degree if (degree_ > 360) { degree_ = 360; - std::cout << "Inputted degree of GeoPotential is too large for EGM96 " + std::cout << "Inputted degree of Geopotential is too large for EGM96 " "model(limit is 360)\n"; - std::cout << "degree of GeoPotential set as " << degree_ << "\n"; + std::cout << "degree of Geopotential set as " << degree_ << "\n"; } else if (degree_ <= 1) { degree_ = 0; } @@ -38,12 +38,12 @@ GeoPotential::GeoPotential(const int degree, const std::string file_path, const if (degree_ >= 2) { if (!ReadCoefficientsEgm96(file_path)) { degree_ = 0; - std::cout << "degree of GeoPotential set as " << degree_ << "\n"; + std::cout << "degree of Geopotential set as " << degree_ << "\n"; } } } -bool GeoPotential::ReadCoefficientsEgm96(std::string file_name) { +bool Geopotential::ReadCoefficientsEgm96(std::string file_name) { std::ifstream coeff_file(file_name); if (!coeff_file.is_open()) { std::cerr << "file open error:Geopotential\n"; @@ -65,7 +65,7 @@ bool GeoPotential::ReadCoefficientsEgm96(std::string file_name) { return true; } -void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynamics &dynamics) { +void Geopotential::Update(const LocalEnvironment &local_environment, const Dynamics &dynamics) { #ifdef DEBUG_GEOPOTENTIAL chrono::system_clock::time_point start, end; start = chrono::system_clock::now(); @@ -83,7 +83,7 @@ void GeoPotential::Update(const LocalEnvironment &local_environment, const Dynam acceleration_i_m_s2_ = trans_ecef2eci * acceleration_ecef_m_s2_; } -void GeoPotential::CalcAccelerationEcef(const libra::Vector<3> &position_ecef_m) { +void Geopotential::CalcAccelerationEcef(const libra::Vector<3> &position_ecef_m) { ecef_x_m_ = position_ecef_m[0]; ecef_y_m_ = position_ecef_m[1]; ecef_z_m_ = position_ecef_m[2]; @@ -147,7 +147,7 @@ void GeoPotential::CalcAccelerationEcef(const libra::Vector<3> &position_ecef_m) return; } -void GeoPotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev, const double w_prev) { +void Geopotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev, const double w_prev) { if (n_ != m_) return; double n_d = (double)n_; @@ -166,7 +166,7 @@ void GeoPotential::v_w_nn_update(double *v_nn, double *w_nn, const double v_prev return; } -void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2) { +void Geopotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev, const double w_prev, const double v_prev2, const double w_prev2) { if (n_ == m_) return; double m_d = (double)m_; @@ -190,7 +190,7 @@ void GeoPotential::v_w_nm_update(double *v_nm, double *w_nm, const double v_prev return; } -std::string GeoPotential::GetLogHeader() const { +std::string Geopotential::GetLogHeader() const { std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL @@ -202,7 +202,7 @@ std::string GeoPotential::GetLogHeader() const { return str_tmp; } -std::string GeoPotential::GetLogValue() const { +std::string Geopotential::GetLogValue() const { std::string str_tmp = ""; #ifdef DEBUG_GEOPOTENTIAL diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index caf22922c..8d577400a 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -15,19 +15,19 @@ #include "acceleration_disturbance.hpp" /** - * @class GeoPotential + * @class Geopotential * @brief Class to calculate the high-order earth gravity acceleration */ -class GeoPotential : public AccelerationDisturbance { +class Geopotential : public AccelerationDisturbance { public: /** - * @fn GeoPotential + * @fn Geopotential * @brief Constructor * @param [in] degree: Maximum degree setting to calculate the geo-potential * @param [in] file_path: EGM96 coefficients file path * @param [in] is_calculation_enabled: Calculation flag */ - GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled = true); + Geopotential(const int degree, const std::string file_path, const bool is_calculation_enabled = true); /** * @fn Update diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 11fbd7802..62c9c40c4 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -21,14 +21,14 @@ class GravityGradient : public SimpleDisturbance { public: /** - * @fn GeoPotential + * @fn Geopotential * @brief Default Constructor * @param [in] is_calculation_enabled: Calculation flag * @note mu is automatically set as earth's gravitational constant */ GravityGradient(const bool is_calculation_enabled = true); /** - * @fn GeoPotential + * @fn Geopotential * @brief Constructor * @param [in] gravity_constant_m3_s2: Gravitational constant [m3/s2] * @param [in] is_calculation_enabled: Calculation flag diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index 75561e730..f233137fa 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -74,7 +74,7 @@ MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_pa return mag_disturbance; } -GeoPotential InitGeoPotential(const std::string initialize_file_path) { +Geopotential InitGeoPotential(const std::string initialize_file_path) { auto conf = IniAccess(initialize_file_path); const char* section = "GEOPOTENTIAL"; @@ -82,7 +82,7 @@ GeoPotential InitGeoPotential(const std::string initialize_file_path) { const std::string coefficients_file_path = conf.ReadString(section, "coefficients_file_path"); const bool is_calc_enable = conf.ReadEnable(section, CALC_LABEL); - GeoPotential geopotential_disturbance(degree, coefficients_file_path, is_calc_enable); + Geopotential geopotential_disturbance(degree, coefficients_file_path, is_calc_enable); geopotential_disturbance.is_log_enabled_ = conf.ReadEnable(section, LOG_LABEL); return geopotential_disturbance; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index bd37f1a90..3183a55f0 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -57,10 +57,10 @@ MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_pa /** * @fn InitGeoPotential - * @brief Initialize GeoPotential class with earth gravitational constant + * @brief Initialize Geopotential class with earth gravitational constant * @param [in] initialize_file_path: Initialize file path */ -GeoPotential InitGeoPotential(const std::string initialize_file_path); +Geopotential InitGeoPotential(const std::string initialize_file_path); /** * @fn InitThirdBodyGravity From dbc51bee92a9a701d45cbf2e8430783cdfa18539 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 13:08:21 +0100 Subject: [PATCH 1017/1086] Fix comments --- src/disturbances/gravity_gradient.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 62c9c40c4..0f620ff24 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -21,14 +21,14 @@ class GravityGradient : public SimpleDisturbance { public: /** - * @fn Geopotential + * @fn GravityGradient * @brief Default Constructor * @param [in] is_calculation_enabled: Calculation flag * @note mu is automatically set as earth's gravitational constant */ GravityGradient(const bool is_calculation_enabled = true); /** - * @fn Geopotential + * @fn GravityGradient * @brief Constructor * @param [in] gravity_constant_m3_s2: Gravitational constant [m3/s2] * @param [in] is_calculation_enabled: Calculation flag From c15173fe28fa97d6ffad1acb813615ee483aac25 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:00:17 +0100 Subject: [PATCH 1018/1086] Fix disturbance base class --- .../initialize_files/sample_disturbance.ini | 4 +- .../sample_simulation_base.ini | 2 +- src/disturbances/disturbance.hpp | 12 ++++- src/disturbances/disturbances.cpp | 49 ++++++++----------- src/disturbances/disturbances.hpp | 13 ++--- src/disturbances/geopotential.cpp | 2 +- src/disturbances/geopotential.hpp | 4 +- src/disturbances/gravity_gradient.cpp | 2 +- src/disturbances/gravity_gradient.hpp | 4 +- src/disturbances/magnetic_disturbance.cpp | 2 +- src/disturbances/magnetic_disturbance.hpp | 4 +- src/disturbances/surface_force.cpp | 2 +- src/disturbances/surface_force.hpp | 4 +- src/disturbances/third_body_gravity.cpp | 2 +- src/disturbances/third_body_gravity.hpp | 4 +- 15 files changed, 54 insertions(+), 56 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index 32da0bd19..da05f11b9 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -1,6 +1,6 @@ [GEOPOTENTIAL] // Enable only when the center object is defined as the Earth -calculation = DISABLE +calculation = ENABLE logging = ENABLE degree = 4 coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii @@ -34,7 +34,7 @@ logging = ENABLE [THIRD_BODY_GRAVITY] -calculation = DISABLE +calculation = ENABLE logging = ENABLE // The number of gravity-generating bodies other than the central body diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 62dc896bb..084f496a9 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -3,7 +3,7 @@ simulation_start_time_utc = 2020/01/01 12:00:00.0 // Simulation duration [sec] -simulation_duration_s = 200 +simulation_duration_s = 10000 // Simulation step time [sec] // Minimum time step for the entire simulation diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index 25122d05e..bea7798a1 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -6,27 +6,35 @@ #ifndef S2E_DISTURBANCES_DISTURBANCE_HPP_ #define S2E_DISTURBANCES_DISTURBANCE_HPP_ +#include "../environment/local/local_environment.hpp" #include "../library/math/vector.hpp" /** * @class Disturbance * @brief Base class for a disturbance */ -class Disturbance { +class Disturbance : public ILoggable { public: /** * @fn Disturbance * @brief Constructor * @param [in] is_calculation_enabled: Calculation flag + * @param [in] is_attitude_dependent: Attitude dependent flag */ Disturbance(const bool is_calculation_enabled = true, const bool is_attitude_dependent = true) : is_calculation_enabled_(is_calculation_enabled), is_attitude_dependent_(is_attitude_dependent) { force_b_N_ = libra::Vector<3>(0.0); torque_b_Nm_ = libra::Vector<3>(0.0); - acceleration_b_m_s2_ = libra::Vector<3>(0.0); + acceleration_i_m_s2_ = libra::Vector<3>(0.0); acceleration_b_m_s2_ = libra::Vector<3>(0.0); } + /** + * @fn ~Disturbance + * @brief Destructor + */ + virtual ~Disturbance() {} + /** * @fn UpdateIfEnabled * @brief Update calculated disturbance when the calculation flag is true diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index b5493d989..51a39176c 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -23,41 +23,34 @@ Disturbances::Disturbances(const SimulationConfiguration* simulation_configurati } Disturbances::~Disturbances() { - for (auto dist : disturbances_list_) { - delete dist; - } - - for (auto acc_dist : acceleration_disturbances_list_) { - delete acc_dist; + for (auto disturbance : disturbances_list_) { + delete disturbance; } } void Disturbances::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics, const SimulationTime* simulation_time) { - // Update disturbances that depend on the attitude (and the position) - if (simulation_time->GetAttitudePropagateFlag()) { - InitializeForceAndTorque(); - for (auto dist : disturbances_list_) { - dist->UpdateIfEnabled(local_environment, dynamics); - total_torque_b_Nm_ += dist->GetTorque_b_Nm(); - total_force_b_N_ += dist->GetForce_b_N(); - } - } - // Update disturbances that depend only on the position - if (simulation_time->GetOrbitPropagateFlag()) { - InitializeAcceleration(); - for (auto acc_dist : acceleration_disturbances_list_) { - acc_dist->UpdateIfEnabled(local_environment, dynamics); - total_acceleration_i_m_s2_ += acc_dist->GetAcceleration_i_m_s2(); + InitializeForceAndTorque(); + InitializeAcceleration(); + + for (auto disturbance : disturbances_list_) { + if (simulation_time->GetOrbitPropagateFlag()) { + // Update disturbances that depend only on the position + disturbance->UpdateIfEnabled(local_environment, dynamics); + } else if (simulation_time->GetAttitudePropagateFlag()) { + // Update disturbances that depend on the attitude (and the position) + if (disturbance->IsAttitudeDependent() == true) { + disturbance->UpdateIfEnabled(local_environment, dynamics); + } } + total_torque_b_Nm_ += disturbance->GetTorque_b_Nm(); + total_force_b_N_ += disturbance->GetForce_b_N(); + total_acceleration_i_m_s2_ += disturbance->GetAcceleration_i_m_s2(); } } void Disturbances::LogSetup(Logger& logger) { - for (auto dist : disturbances_list_) { - logger.AddLogList(dist); - } - for (auto acc_dist : acceleration_disturbances_list_) { - logger.AddLogList(acc_dist); + for (auto disturbance : disturbances_list_) { + logger.AddLogList(disturbance); } logger.CopyFileToLogDirectory(initialize_file_name_); } @@ -77,7 +70,7 @@ void Disturbances::InitializeInstances(const SimulationConfiguration* simulation ThirdBodyGravity* third_body_gravity = new ThirdBodyGravity(InitThirdBodyGravity(initialize_file_name_, simulation_configuration->initialize_base_file_name_)); - acceleration_disturbances_list_.push_back(third_body_gravity); + disturbances_list_.push_back(third_body_gravity); if (global_environment->GetCelestialInformation().GetCenterBodyName() != "EARTH") return; // Earth only disturbances (TODO: implement disturbances for other center bodies) @@ -89,7 +82,7 @@ void Disturbances::InitializeInstances(const SimulationConfiguration* simulation disturbances_list_.push_back(mag_dist); GeoPotential* geopotential = new GeoPotential(InitGeoPotential(initialize_file_name_)); - acceleration_disturbances_list_.push_back(geopotential); + disturbances_list_.push_back(geopotential); } void Disturbances::InitializeForceAndTorque() { diff --git a/src/disturbances/disturbances.hpp b/src/disturbances/disturbances.hpp index 173481ade..d5eeaaa40 100644 --- a/src/disturbances/disturbances.hpp +++ b/src/disturbances/disturbances.hpp @@ -10,8 +10,7 @@ #include "../environment/global/simulation_time.hpp" #include "../simulation/spacecraft/structure/structure.hpp" -#include "acceleration_disturbance.hpp" -#include "simple_disturbance.hpp" +#include "disturbance.hpp" class Logger; @@ -73,12 +72,10 @@ class Disturbances { private: std::string initialize_file_name_; //!< Initialization file name - std::vector disturbances_list_; //!< List of disturbances - Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] - Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] - - std::vector acceleration_disturbances_list_; //!< List of acceleration disturbances - Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] + std::vector disturbances_list_; //!< List of disturbances + Vector<3> total_torque_b_Nm_; //!< Total disturbance torque in the body frame [Nm] + Vector<3> total_force_b_N_; //!< Total disturbance force in the body frame [N] + Vector<3> total_acceleration_i_m_s2_; //!< Total disturbance acceleration in the inertial frame [m/s2] /** * @fn InitializeInstances diff --git a/src/disturbances/geopotential.cpp b/src/disturbances/geopotential.cpp index 99ac8c41c..38f416bb5 100644 --- a/src/disturbances/geopotential.cpp +++ b/src/disturbances/geopotential.cpp @@ -16,7 +16,7 @@ // #define DEBUG_GEOPOTENTIAL GeoPotential::GeoPotential(const int degree, const std::string file_path, const bool is_calculation_enabled) - : AccelerationDisturbance(is_calculation_enabled), degree_(degree) { + : Disturbance(is_calculation_enabled, false), degree_(degree) { // Initialize acceleration_ecef_m_s2_ = libra::Vector<3>(0.0); debug_pos_ecef_m_ = libra::Vector<3>(0.0); diff --git a/src/disturbances/geopotential.hpp b/src/disturbances/geopotential.hpp index caf22922c..0563b4ee3 100644 --- a/src/disturbances/geopotential.hpp +++ b/src/disturbances/geopotential.hpp @@ -12,13 +12,13 @@ #include "../library/math/matrix.hpp" #include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" -#include "acceleration_disturbance.hpp" +#include "disturbance.hpp" /** * @class GeoPotential * @brief Class to calculate the high-order earth gravity acceleration */ -class GeoPotential : public AccelerationDisturbance { +class GeoPotential : public Disturbance { public: /** * @fn GeoPotential diff --git a/src/disturbances/gravity_gradient.cpp b/src/disturbances/gravity_gradient.cpp index 7390771db..c03914f37 100644 --- a/src/disturbances/gravity_gradient.cpp +++ b/src/disturbances/gravity_gradient.cpp @@ -14,7 +14,7 @@ GravityGradient::GravityGradient(const bool is_calculation_enabled) : GravityGradient(environment::earth_gravitational_constant_m3_s2, is_calculation_enabled) {} GravityGradient::GravityGradient(const double gravity_constant_m3_s2, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), gravity_constant_m3_s2_(gravity_constant_m3_s2) {} + : Disturbance(is_calculation_enabled, true), gravity_constant_m3_s2_(gravity_constant_m3_s2) {} void GravityGradient::Update(const LocalEnvironment& local_environment, const Dynamics& dynamics) { // TODO: use structure information to get inertia tensor diff --git a/src/disturbances/gravity_gradient.hpp b/src/disturbances/gravity_gradient.hpp index 11fbd7802..44f557b95 100644 --- a/src/disturbances/gravity_gradient.hpp +++ b/src/disturbances/gravity_gradient.hpp @@ -12,13 +12,13 @@ #include "../library/math/matrix.hpp" #include "../library/math/matrix_vector.hpp" #include "../library/math/vector.hpp" -#include "simple_disturbance.hpp" +#include "disturbance.hpp" /** * @class GravityGradient * @brief Class to calculate the gravity gradient torque */ -class GravityGradient : public SimpleDisturbance { +class GravityGradient : public Disturbance { public: /** * @fn GeoPotential diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index c61600e7f..5fbfbea3a 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -13,7 +13,7 @@ #include "../library/randomization/random_walk.hpp" MagneticDisturbance::MagneticDisturbance(const ResidualMagneticMoment& rmm_params, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), residual_magnetic_moment_(rmm_params) { + : Disturbance(is_calculation_enabled, true), residual_magnetic_moment_(rmm_params) { rmm_b_Am2_ = residual_magnetic_moment_.GetConstantValue_b_Am2(); } diff --git a/src/disturbances/magnetic_disturbance.hpp b/src/disturbances/magnetic_disturbance.hpp index 7a8f018ca..f523511b8 100644 --- a/src/disturbances/magnetic_disturbance.hpp +++ b/src/disturbances/magnetic_disturbance.hpp @@ -11,13 +11,13 @@ #include "../library/logger/loggable.hpp" #include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/residual_magnetic_moment.hpp" -#include "simple_disturbance.hpp" +#include "disturbance.hpp" /** * @class MagneticDisturbance * @brief Class to calculate the magnetic disturbance torque */ -class MagneticDisturbance : public SimpleDisturbance { +class MagneticDisturbance : public Disturbance { public: /** * @fn MagneticDisturbance diff --git a/src/disturbances/surface_force.cpp b/src/disturbances/surface_force.cpp index c074d2358..51c94c4aa 100644 --- a/src/disturbances/surface_force.cpp +++ b/src/disturbances/surface_force.cpp @@ -8,7 +8,7 @@ #include "../library/math/vector.hpp" SurfaceForce::SurfaceForce(const std::vector& surfaces, const libra::Vector<3>& center_of_gravity_b_m, const bool is_calculation_enabled) - : SimpleDisturbance(is_calculation_enabled), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { + : Disturbance(is_calculation_enabled, true), surfaces_(surfaces), center_of_gravity_b_m_(center_of_gravity_b_m) { // Initialize vectors int num = surfaces_.size(); normal_coefficients_.assign(num, 0.0); diff --git a/src/disturbances/surface_force.hpp b/src/disturbances/surface_force.hpp index 0c97e282a..ad82c9fba 100644 --- a/src/disturbances/surface_force.hpp +++ b/src/disturbances/surface_force.hpp @@ -13,13 +13,13 @@ #include "../library/math/quaternion.hpp" #include "../library/math/vector.hpp" #include "../simulation/spacecraft/structure/surface.hpp" -#include "simple_disturbance.hpp" +#include "disturbance.hpp" /** * @class ThirdBodyGravity * @brief Class to calculate third body gravity disturbance */ -class SurfaceForce : public SimpleDisturbance { +class SurfaceForce : public Disturbance { public: /** * @fn SurfaceForce diff --git a/src/disturbances/third_body_gravity.cpp b/src/disturbances/third_body_gravity.cpp index 61f3a358a..7c245e471 100644 --- a/src/disturbances/third_body_gravity.cpp +++ b/src/disturbances/third_body_gravity.cpp @@ -6,7 +6,7 @@ #include "third_body_gravity.hpp" ThirdBodyGravity::ThirdBodyGravity(std::set third_body_list, const bool is_calculation_enabled) - : AccelerationDisturbance(is_calculation_enabled), third_body_list_(third_body_list) { + : Disturbance(is_calculation_enabled, false), third_body_list_(third_body_list) { acceleration_i_m_s2_ = libra::Vector<3>(0.0); } diff --git a/src/disturbances/third_body_gravity.hpp b/src/disturbances/third_body_gravity.hpp index 244178adf..4f7113e3c 100644 --- a/src/disturbances/third_body_gravity.hpp +++ b/src/disturbances/third_body_gravity.hpp @@ -12,13 +12,13 @@ #include "../library/logger/loggable.hpp" #include "../library/math/vector.hpp" -#include "acceleration_disturbance.hpp" +#include "disturbance.hpp" /** * @class ThirdBodyGravity * @brief Class to calculate third body gravity disturbance */ -class ThirdBodyGravity : public AccelerationDisturbance { +class ThirdBodyGravity : public Disturbance { public: /** * @fn ThirdBodyGravity From bce8f6364db8f84f07ac9adbe27102f6bcb40e77 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:08:18 +0100 Subject: [PATCH 1019/1086] Revert default setting --- data/sample/initialize_files/sample_disturbance.ini | 4 ++-- data/sample/initialize_files/sample_simulation_base.ini | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/sample_disturbance.ini b/data/sample/initialize_files/sample_disturbance.ini index da05f11b9..32da0bd19 100644 --- a/data/sample/initialize_files/sample_disturbance.ini +++ b/data/sample/initialize_files/sample_disturbance.ini @@ -1,6 +1,6 @@ [GEOPOTENTIAL] // Enable only when the center object is defined as the Earth -calculation = ENABLE +calculation = DISABLE logging = ENABLE degree = 4 coefficients_file_path = ../../../ExtLibraries/GeoPotential/egm96_to360.ascii @@ -34,7 +34,7 @@ logging = ENABLE [THIRD_BODY_GRAVITY] -calculation = ENABLE +calculation = DISABLE logging = ENABLE // The number of gravity-generating bodies other than the central body diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 084f496a9..62dc896bb 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -3,7 +3,7 @@ simulation_start_time_utc = 2020/01/01 12:00:00.0 // Simulation duration [sec] -simulation_duration_s = 10000 +simulation_duration_s = 200 // Simulation step time [sec] // Minimum time step for the entire simulation From d9d7d820d8525def6cdfb6e71d18eb3f6f115e5e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:20:17 +0100 Subject: [PATCH 1020/1086] Move gen_graph to Plot --- {data/sample => scripts/Plot}/gen_graph.sh | 0 {data/sample => scripts/Plot}/graph.toml | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename {data/sample => scripts/Plot}/gen_graph.sh (100%) rename {data/sample => scripts/Plot}/graph.toml (100%) diff --git a/data/sample/gen_graph.sh b/scripts/Plot/gen_graph.sh similarity index 100% rename from data/sample/gen_graph.sh rename to scripts/Plot/gen_graph.sh diff --git a/data/sample/graph.toml b/scripts/Plot/graph.toml similarity index 100% rename from data/sample/graph.toml rename to scripts/Plot/graph.toml From acb30a1ba2c1a1633b9bf6d76315718b41e1b6f4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:21:50 +0100 Subject: [PATCH 1021/1086] Fix working directory --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 3ba2d4975..9d0f56420 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -200,7 +200,7 @@ jobs: ../../S2E - name: generate graph - working-directory: ./data/sample + working-directory: ./scripts/Plot run: | sudo apt-get install -y gnuplot pip3 install yq From 99b27f875e689e7792a67391a211870c05c068e6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:34:28 +0100 Subject: [PATCH 1022/1086] Fix path to log file --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 9d0f56420..ab9b63229 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -204,7 +204,7 @@ jobs: run: | sudo apt-get install -y gnuplot pip3 install yq - LOG=$(ls logs/logs_*/*.csv) + LOG=$(ls ../../data/sample/logs/logs_*/*.csv) echo "plot $LOG" ./gen_graph.sh "${LOG}" ls From 2ab6690f4203ad622c327f01106c023af7d144d2 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:41:42 +0100 Subject: [PATCH 1023/1086] Fix endian.h to endian.hpp --- src/library/utilities/endian.cpp | 4 ++-- src/library/utilities/{endian.h => endian.hpp} | 0 2 files changed, 2 insertions(+), 2 deletions(-) rename src/library/utilities/{endian.h => endian.hpp} (100%) diff --git a/src/library/utilities/endian.cpp b/src/library/utilities/endian.cpp index bdc1e5cc1..514879814 100644 --- a/src/library/utilities/endian.cpp +++ b/src/library/utilities/endian.cpp @@ -1,9 +1,9 @@ /** - * @file endian.h + * @file endian.cpp * @brief Function to consider the endian */ -#include "endian.h" +#include "endian.hpp" #include diff --git a/src/library/utilities/endian.h b/src/library/utilities/endian.hpp similarity index 100% rename from src/library/utilities/endian.h rename to src/library/utilities/endian.hpp From 5afb893ac25877957c902e794ad39cfed9d6f2a8 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:42:35 +0100 Subject: [PATCH 1024/1086] Fix slip.h to slip.hpp --- src/library/utilities/slip.cpp | 2 +- src/library/utilities/{slip.h => slip.hpp} | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) rename src/library/utilities/{slip.h => slip.hpp} (98%) diff --git a/src/library/utilities/slip.cpp b/src/library/utilities/slip.cpp index ae7d21bb5..6f2192409 100644 --- a/src/library/utilities/slip.cpp +++ b/src/library/utilities/slip.cpp @@ -3,7 +3,7 @@ * @brief Functions for SLIP(Serial Line Internet Protocol) encoding */ -#include "slip.h" +#include "slip.hpp" #include #include diff --git a/src/library/utilities/slip.h b/src/library/utilities/slip.hpp similarity index 98% rename from src/library/utilities/slip.h rename to src/library/utilities/slip.hpp index 6ab5e4fe1..b5355bb5d 100644 --- a/src/library/utilities/slip.h +++ b/src/library/utilities/slip.hpp @@ -1,5 +1,5 @@ /** - * @file slip.h + * @file slip.hpp * @brief Functions for SLIP(Serial Line Internet Protocol) encoding */ From 3c16c86e37fa488880f117edda023964e1a7e07c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 14:42:49 +0100 Subject: [PATCH 1025/1086] Fix comment --- src/library/utilities/endian.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/library/utilities/endian.hpp b/src/library/utilities/endian.hpp index ce9ffff0f..27195efd1 100644 --- a/src/library/utilities/endian.hpp +++ b/src/library/utilities/endian.hpp @@ -1,5 +1,5 @@ /** - * @file endian.h + * @file endian.hpp * @brief Function to consider the endian */ From 5b66b89d26d2cf59515624d9dcedb11b302500b4 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 13 Mar 2023 15:09:12 +0100 Subject: [PATCH 1026/1086] Fix include guard --- src/components/base/gpio_connection_with_obc.hpp | 6 +++--- src/library/communication/com_port_interface.hpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/base/gpio_connection_with_obc.hpp b/src/components/base/gpio_connection_with_obc.hpp index 7e3c5fb0b..397456674 100644 --- a/src/components/base/gpio_connection_with_obc.hpp +++ b/src/components/base/gpio_connection_with_obc.hpp @@ -4,8 +4,8 @@ * TODO: consider relation with IGPIOCompo */ -#ifndef S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ -#define S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ +#ifndef S2E_COMPONENTS_BASE_GPIO_CONNECTION_WITH_OBC_HPP_ +#define S2E_COMPONENTS_BASE_GPIO_CONNECTION_WITH_OBC_HPP_ #include "../real/cdh/on_board_computer.hpp" @@ -50,4 +50,4 @@ class GpioConnectionWithObc { OnBoardComputer* obc_; //!< The communication target OBC }; -#endif // S2E_COMPONENTS_GPIO_CONNECTION_WITH_OBC_HPP_ +#endif // S2E_COMPONENTS_BASE_GPIO_CONNECTION_WITH_OBC_HPP_ diff --git a/src/library/communication/com_port_interface.hpp b/src/library/communication/com_port_interface.hpp index 57657fd2f..03ccd568b 100644 --- a/src/library/communication/com_port_interface.hpp +++ b/src/library/communication/com_port_interface.hpp @@ -6,8 +6,8 @@ * Reference: https://docs.microsoft.com/ja-jp/dotnet/api/system.io.ports.serialport?view=netframework-4.7.2 */ -#ifndef S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ -#define S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ +#ifndef S2E_LIBRARY_COMMUNICATION_COM_PORT_INTERFACE_HPP_ +#define S2E_LIBRARY_COMMUNICATION_COM_PORT_INTERFACE_HPP_ #include #include @@ -105,4 +105,4 @@ class ComPortInterface { msclr::gcroot rx_buf_; //!< RX Buffer }; -#endif // S2E_INTERFACE_HILS_COM_PORT_INTERFACE_HPP_ +#endif // S2E_LIBRARY_COMMUNICATION_COM_PORT_INTERFACE_HPP_ From e54ae1bfc25067e6728ea2952141f0c8934791a1 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Wed, 15 Mar 2023 00:11:42 +0900 Subject: [PATCH 1027/1086] add tx_bitrate in Antenna --- src/components/real/communication/antenna.cpp | 6 +- src/components/real/communication/antenna.hpp | 12 +++- .../ground_station_calculator.cpp | 59 +++++++++++-------- .../ground_station_calculator.hpp | 32 +++++----- .../real/communication/initialize_antenna.cpp | 3 +- 5 files changed, 66 insertions(+), 46 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index c9e36df92..0a7673741 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -9,7 +9,7 @@ #include Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency_MHz, const Vector<4> tx_parameters, const Vector<4> rx_parameters) + const double frequency_MHz, const Vector<5> tx_parameters, const Vector<4> rx_parameters) : component_id_(component_id), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_MHz_(frequency_MHz) { quaternion_b2c_ = quaternion_b2c; @@ -18,6 +18,7 @@ Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c tx_parameters_.gain_dBi_ = tx_parameters[1]; tx_parameters_.loss_feeder_dB_ = tx_parameters[2]; tx_parameters_.loss_pointing_dB_ = tx_parameters[3]; + tx_bitrate_bps_ = tx_parameters[4]; rx_parameters_.gain_dBi_ = rx_parameters[0]; rx_parameters_.loss_feeder_dB_ = rx_parameters[1]; @@ -42,13 +43,14 @@ Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c } Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, + const double tx_bitrate_bps, const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, const double rx_system_noise_temperature_K, const AntennaParameters rx_parameters) : component_id_(component_id), quaternion_b2c_(quaternion_b2c), is_transmitter_(is_transmitter), is_receiver_(is_receiver), frequency_MHz_(frequency_MHz), + tx_bitrate_bps_(tx_bitrate_bps), tx_output_power_W_(tx_output_power_W), tx_parameters_(tx_parameters), rx_system_noise_temperature_K_(rx_system_noise_temperature_K), diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 4344a26a0..2b69b891d 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -55,7 +55,7 @@ class Antenna { * @param [in] rx_parameters: gain, loss_feeder, loss_pointing, system_temperature for RX */ Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency_MHz, const Vector<4> tx_parameters, const Vector<4> rx_parameters); + const double frequency_MHz, const Vector<5> tx_parameters, const Vector<4> rx_parameters); /** * @fn Antenna @@ -65,13 +65,14 @@ class Antenna { * @param [in] is_transmitter: Antenna for transmitter or not * @param [in] is_receiver: Antenna for receiver or not * @param [in] frequency_MHz: Center Frequency [MHz] + * @param [in] tx_bitrate_bps: Transmit bitrate [bps] * @param [in] tx_output_power_W: Transmit output power [W] * @param [in] tx_parameters: TX antenna parameters * @param [in] rx_system_noise_temperature_K: Receive system noise temperature [K] * @param [in] rx_parameters: RX antenna parameters */ Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, + const double frequency_MHz, const double tx_bitrate_bps, const double tx_output_power_W, const AntennaParameters tx_parameters, const double rx_system_noise_temperature_K, const AntennaParameters rx_parameters); /** * @fn ~Antenna @@ -103,6 +104,12 @@ class Antenna { */ inline double GetFrequency_MHz() const { return frequency_MHz_; } /** + * @fn GetBitrate + * @brief Return bitrate [bps] + */ + inline double GetBitrate() const { return tx_bitrate_bps_; } + /** + * * @fn GetQuaternion_b2c * @brief Return quaternion from body to component */ @@ -128,6 +135,7 @@ class Antenna { double frequency_MHz_; //!< Center Frequency [MHz] // Tx info + double tx_bitrate_bps_; //!< Transmit bitrate [bps] double tx_output_power_W_; //!< Transmit output power [W] AntennaParameters tx_parameters_; //!< Tx parameters double tx_eirp_dBW_; //!< Transmit EIRP(Equivalent Isotropic Radiated Power) [dBW] diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index e21058fd8..a014a15b9 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -26,12 +26,12 @@ GroundStationCalculator::GroundStationCalculator(const double loss_polarization_ GroundStationCalculator::~GroundStationCalculator() {} -void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { +void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna) { bool is_visible = ground_station.IsVisible(spacecraft.GetSpacecraftId()); if (is_visible) { - max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); - receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); + max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_antenna, ground_station, ground_station_antenna); + receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_antenna, ground_station, ground_station_antenna); } else { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -39,9 +39,9 @@ void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna } // Private functions -double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { - double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); +double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna) { + double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_) - margin_requirement_dB_; @@ -52,16 +52,16 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A } } -double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, - const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { - double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); +double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, + const GroundStation& ground_station, const Antenna& ground_station_antenna) { + double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(downlink_bitrate_bps_); return cn0_dB - cn0_requirement_dB; } -double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna) { - if (!spacecraft_tx_antenna.IsTransmitter() || !ground_station_rx_antenna.IsReceiver()) { +double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna) { + if (!spacecraft_antenna.IsTransmitter() || !ground_station_antenna.IsReceiver()) { // Check compatibility of transmitter and receiver return 0.0f; } @@ -70,30 +70,39 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; - double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_tx_antenna.GetFrequency_MHz() / 1000.0)); + double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_antenna.GetFrequency_MHz() / 1000.0)); // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; sc_to_gs_i = libra::Normalize(sc_to_gs_i); - Quaternion q_i_to_sc_ant = spacecraft_tx_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); + Quaternion q_i_to_sc_ant = spacecraft_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[2]); - double phi_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[0] / sin(theta_on_sc_antenna_rad)); + double phi_on_sc_antenna_rad = atan2(gs_direction_on_sc_frame[1], gs_direction_on_sc_frame[0]); // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetPosition_ecef_m(); gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); - Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); + Quaternion q_ecef_to_gs_ant = ground_station_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); - double phi_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[0] / sin(theta_on_gs_antenna_rad)); - - // Calc CN0 - double cn0_dBHz = spacecraft_tx_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + - loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - ground_station_rx_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - - 10.0 * log10(environment::boltzmann_constant_J_K); - return cn0_dBHz; + double phi_on_gs_antenna_rad = atan2(sc_direction_on_gs_frame[1], sc_direction_on_gs_frame[0]); + + if (spacecraft_antenna.IsTransmitter()) { + // Calc CN0 + double cn0_dBHz = spacecraft_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + + ground_station_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + 10.0 * log10(environment::boltzmann_constant_J_K); + return cn0_dBHz; + } else { + // Calc CN0 + double cn0_dBHz = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + + spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - + 10.0 * log10(environment::boltzmann_constant_J_K); + return cn0_dBHz; + } } std::string GroundStationCalculator::GetLogHeader() const { diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index ab4ddb01b..284f54114 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -45,12 +45,12 @@ class GroundStationCalculator : public ILoggable { * @fn Update * @brief Update maximum bitrate calculation * @param [in] spacecraft: Spacecraft information - * @param [in] spacecraft_tx_antenna: Antenna mounted on spacecraft + * @param [in] spacecraft_antenna: Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_rx_antenna: Antenna mounted on ground station + * @param [in] ground_station_antenna: Antenna mounted on ground station */ - void Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna); + void Update(const Spacecraft& spacecraft, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna); // Override ILoggable TODO: Maybe we don't need logabble, and this class should be used as library. /** @@ -104,36 +104,36 @@ class GroundStationCalculator : public ILoggable { * @fn CalcMaxBitrate * @brief Calculate the maximum bitrate * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_antenna: Rx Antenna mounted on ground station * @return Max bitrate [Mbps] */ - double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna); + double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna); /** * @fn CalcReceiveMarginOnGs * @brief Calculate receive margin at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_antenna: Rx Antenna mounted on ground station * @return Receive margin [dB] */ - double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna); + double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna); /** * @fn CalcCn0 * @brief Calculate CN0 (Carrier to Noise density ratio) of received signal at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_antenna: Rx Antenna mounted on ground station * @return CN0 [dB] */ - double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, - const Antenna& ground_station_rx_antenna); + double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, + const Antenna& ground_station_antenna); }; #endif // S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ diff --git a/src/components/real/communication/initialize_antenna.cpp b/src/components/real/communication/initialize_antenna.cpp index e1ff30d89..6ab1187c4 100644 --- a/src/components/real/communication/initialize_antenna.cpp +++ b/src/components/real/communication/initialize_antenna.cpp @@ -30,6 +30,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { bool is_receiver = antenna_conf.ReadBoolean(Section, "is_receiver"); double frequency_MHz = antenna_conf.ReadDouble(Section, "frequency_MHz"); + double tx_bitrate_bps = antenna_conf.ReadDouble(Section, "tx_bitrate_bps"); double tx_output_power_W = antenna_conf.ReadDouble(Section, "tx_output_W"); double rx_system_noise_temperature_K = antenna_conf.ReadDouble(Section, "rx_system_noise_temperature_K"); @@ -72,7 +73,7 @@ Antenna InitAntenna(const int antenna_id, const std::string file_name) { rx_parameters.antenna_gain_model = AntennaGainModel::kIsotropic; } - Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency_MHz, tx_output_power_W, tx_parameters, + Antenna antenna(antenna_id, quaternion_b2c, is_transmitter, is_receiver, frequency_MHz, tx_bitrate_bps, tx_output_power_W, tx_parameters, rx_system_noise_temperature_K, rx_parameters); return antenna; } From 6b91bd4ddb2609f7f90206436a542a30f63b475c Mon Sep 17 00:00:00 2001 From: Tomoki Date: Wed, 15 Mar 2023 11:03:53 +0900 Subject: [PATCH 1028/1086] add tx_bitrate --- .../initialize_files/components/ground_station_antenna.ini | 3 +++ data/sample/initialize_files/components/spacecraft_antenna.ini | 3 +++ 2 files changed, 6 insertions(+) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index 86ed52238..fa3ae03aa 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -14,6 +14,9 @@ is_receiver = 1 // frequency [MHz] frequency_MHz = 8200.0 +// bitrate [bps] +tx_bitrate = 10000 + // Parameters for transmitter // RF output power [W] tx_output_W = 1.0 diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 6fdfac644..c402a8fac 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -14,6 +14,9 @@ is_receiver = 1 // frequency [MHz] frequency_MHz = 8200.0 +// bitrate [bps] +tx_bitrate = 100000 + // Parameters for transmitter // RF output power [W] tx_output_W = 1.0 From 4886243032776da4895ff7d9f67125a55374f883 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Wed, 15 Mar 2023 11:14:02 +0900 Subject: [PATCH 1029/1086] rename tx_bitrate --- .../initialize_files/components/ground_station_antenna.ini | 2 +- data/sample/initialize_files/components/spacecraft_antenna.ini | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index fa3ae03aa..d999ae7b6 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -15,7 +15,7 @@ is_receiver = 1 frequency_MHz = 8200.0 // bitrate [bps] -tx_bitrate = 10000 +tx_bitrate_bps = 10000 // Parameters for transmitter // RF output power [W] diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index c402a8fac..9c5f4d255 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -15,7 +15,7 @@ is_receiver = 1 frequency_MHz = 8200.0 // bitrate [bps] -tx_bitrate = 100000 +tx_bitrate_bps = 100000 // Parameters for transmitter // RF output power [W] From e189005ed34562d89d19c47e9a91d2c87b53b9cb Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 08:02:30 +0900 Subject: [PATCH 1030/1086] fix SetAntennaGainModel --- src/components/real/communication/antenna.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 0a7673741..c12bfc588 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -93,9 +93,9 @@ double Antenna::CalcRxGt_dB_K(const double theta_rad, const double phi_rad) cons } AntennaGainModel SetAntennaGainModel(const std::string gain_model_name) { - if (gain_model_name == "kIsotropic") { + if (gain_model_name == "ISOTROPIC") { return AntennaGainModel::kIsotropic; - } else if (gain_model_name == "kRadiationPatternCsv") { + } else if (gain_model_name == "RADIATION_PATTERN_CSV") { return AntennaGainModel::kRadiationPatternCsv; } else { return AntennaGainModel::kIsotropic; From 90a786baba57915f5ab2bea061b435d08d3f7c44 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 08:03:19 +0900 Subject: [PATCH 1031/1086] fix CalcReceiveMarginOnGs --- src/components/real/communication/ground_station_calculator.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index a014a15b9..55fe6b001 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -55,7 +55,7 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, const Antenna& ground_station_antenna) { double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); - double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(downlink_bitrate_bps_); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(spacecraft_antenna.GetBitrate()); return cn0_dB - cn0_requirement_dB; } From 31481029ad719af473ffae03f99258db9bb227a5 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 08:13:14 +0900 Subject: [PATCH 1032/1086] add Log --- src/simulation/ground_station/ground_station.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index de8b5813b..63ba6ca55 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -77,6 +77,7 @@ std::string GroundStation::GetLogHeader() const { std::string legend = head + "sc" + std::to_string(i) + "_visible_flag"; str_tmp += WriteScalar(legend); } + str_tmp += WriteVector("gs_pos", "eci", "m", 3); return str_tmp; } @@ -86,5 +87,6 @@ std::string GroundStation::GetLogValue() const { for (unsigned int i = 0; i < number_of_spacecraft_; i++) { str_tmp += WriteScalar(is_visible_.at(i)); } + str_tmp += WriteVector(position_i_m_); return str_tmp; } From ac9d5bd62ae222a55e37238c8afcc2e320e4d0b6 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 09:18:44 +0900 Subject: [PATCH 1033/1086] fix Antenna class --- src/components/real/communication/antenna.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index c12bfc588..ab92c650e 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -43,7 +43,7 @@ Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c } Antenna::Antenna(const int component_id, const libra::Quaternion& quaternion_b2c, const bool is_transmitter, const bool is_receiver, - const double tx_bitrate_bps, const double frequency_MHz, const double tx_output_power_W, const AntennaParameters tx_parameters, + const double frequency_MHz, const double tx_bitrate_bps, const double tx_output_power_W, const AntennaParameters tx_parameters, const double rx_system_noise_temperature_K, const AntennaParameters rx_parameters) : component_id_(component_id), quaternion_b2c_(quaternion_b2c), From 150f301d6b08ec5f134c196d849b72c9966664f7 Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 10:43:17 +0900 Subject: [PATCH 1034/1086] enable to analyze uplink margin --- .../real/communication/ground_station_calculator.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 55fe6b001..76921455a 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -61,11 +61,6 @@ double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, const Antenna& ground_station_antenna) { - if (!spacecraft_antenna.IsTransmitter() || !ground_station_antenna.IsReceiver()) { - // Check compatibility of transmitter and receiver - return 0.0f; - } - // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); @@ -97,6 +92,8 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante return cn0_dBHz; } else { // Calc CN0 + double testA = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad); + double testB = spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad); double cn0_dBHz = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - From cbf78f923571296574bc98ced51d42cbb2393b9b Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 16:01:27 +0900 Subject: [PATCH 1035/1086] revert antenna_gain_model --- .../initialize_files/components/ground_station_antenna.ini | 4 ++-- .../sample/initialize_files/components/spacecraft_antenna.ini | 4 ++-- src/components/real/communication/antenna.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index d999ae7b6..e250d36e9 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -30,7 +30,7 @@ tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = ISOTROPIC +tx_antenna_gain_model = kIsotropic // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis @@ -58,7 +58,7 @@ rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = ISOTROPIC +rx_antenna_gain_model = kIsotropic // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 9c5f4d255..53ce874e3 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -30,7 +30,7 @@ tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = RADIATION_PATTERN_CSV +tx_antenna_gain_model = kRadiationPatternCsv // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis @@ -58,7 +58,7 @@ rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = RADIATION_PATTERN_CSV +rx_antenna_gain_model = kRadiationPatternCsv // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index ab92c650e..8b466d662 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -93,9 +93,9 @@ double Antenna::CalcRxGt_dB_K(const double theta_rad, const double phi_rad) cons } AntennaGainModel SetAntennaGainModel(const std::string gain_model_name) { - if (gain_model_name == "ISOTROPIC") { + if (gain_model_name == "kIsotropic") { return AntennaGainModel::kIsotropic; - } else if (gain_model_name == "RADIATION_PATTERN_CSV") { + } else if (gain_model_name == "kRadiationPatternCsv") { return AntennaGainModel::kRadiationPatternCsv; } else { return AntennaGainModel::kIsotropic; From 4a5f02549287d23cbce9ca077fe0f319096b387a Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 16:10:51 +0900 Subject: [PATCH 1036/1086] rename function GetBitrate() --- src/components/real/communication/antenna.hpp | 2 +- src/components/real/communication/ground_station_calculator.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/components/real/communication/antenna.hpp b/src/components/real/communication/antenna.hpp index 2b69b891d..098ef1ec2 100644 --- a/src/components/real/communication/antenna.hpp +++ b/src/components/real/communication/antenna.hpp @@ -107,7 +107,7 @@ class Antenna { * @fn GetBitrate * @brief Return bitrate [bps] */ - inline double GetBitrate() const { return tx_bitrate_bps_; } + inline double GetBitrate_bps() const { return tx_bitrate_bps_; } /** * * @fn GetQuaternion_b2c diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 76921455a..3c26fc2ca 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -55,7 +55,7 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, const Antenna& ground_station_antenna) { double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); - double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(spacecraft_antenna.GetBitrate()); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(spacecraft_antenna.GetBitrate_bps()); return cn0_dB - cn0_requirement_dB; } From 170a7f023b0953bcb61ee8df88fe13b131c223ec Mon Sep 17 00:00:00 2001 From: Tomoki Date: Thu, 16 Mar 2023 16:13:22 +0900 Subject: [PATCH 1037/1086] remove test variables --- src/components/real/communication/ground_station_calculator.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 3c26fc2ca..685069833 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -92,8 +92,6 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante return cn0_dBHz; } else { // Calc CN0 - double testA = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad); - double testB = spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad); double cn0_dBHz = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - From 5e2d1eaa7aa4d2ed8c150a1deeafbb09f5101f0d Mon Sep 17 00:00:00 2001 From: Tomoki Date: Fri, 17 Mar 2023 00:44:02 +0900 Subject: [PATCH 1038/1086] revert gain_model_name --- .../initialize_files/components/ground_station_antenna.ini | 4 ++-- .../sample/initialize_files/components/spacecraft_antenna.ini | 4 ++-- src/components/real/communication/antenna.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/data/sample/initialize_files/components/ground_station_antenna.ini b/data/sample/initialize_files/components/ground_station_antenna.ini index e250d36e9..d999ae7b6 100644 --- a/data/sample/initialize_files/components/ground_station_antenna.ini +++ b/data/sample/initialize_files/components/ground_station_antenna.ini @@ -30,7 +30,7 @@ tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = kIsotropic +tx_antenna_gain_model = ISOTROPIC // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis @@ -58,7 +58,7 @@ rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = kIsotropic +rx_antenna_gain_model = ISOTROPIC // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis diff --git a/data/sample/initialize_files/components/spacecraft_antenna.ini b/data/sample/initialize_files/components/spacecraft_antenna.ini index 53ce874e3..9c5f4d255 100644 --- a/data/sample/initialize_files/components/spacecraft_antenna.ini +++ b/data/sample/initialize_files/components/spacecraft_antenna.ini @@ -30,7 +30,7 @@ tx_loss_pointing_dB = 0.0 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -tx_antenna_gain_model = kRadiationPatternCsv +tx_antenna_gain_model = RADIATION_PATTERN_CSV // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis @@ -58,7 +58,7 @@ rx_system_noise_temperature_K = 230 // Antenna gain model // ISOTROPIC: Ideal isotropic antenna // RADIATION_PATTERN_CSV: Radiation pattern obtained by CSV files -rx_antenna_gain_model = kRadiationPatternCsv +rx_antenna_gain_model = RADIATION_PATTERN_CSV // Gain for ISOTROPIC mode [dBi] // Generally, it is zero but users can set any value for ideal analysis diff --git a/src/components/real/communication/antenna.cpp b/src/components/real/communication/antenna.cpp index 8b466d662..ab92c650e 100644 --- a/src/components/real/communication/antenna.cpp +++ b/src/components/real/communication/antenna.cpp @@ -93,9 +93,9 @@ double Antenna::CalcRxGt_dB_K(const double theta_rad, const double phi_rad) cons } AntennaGainModel SetAntennaGainModel(const std::string gain_model_name) { - if (gain_model_name == "kIsotropic") { + if (gain_model_name == "ISOTROPIC") { return AntennaGainModel::kIsotropic; - } else if (gain_model_name == "kRadiationPatternCsv") { + } else if (gain_model_name == "RADIATION_PATTERN_CSV") { return AntennaGainModel::kRadiationPatternCsv; } else { return AntennaGainModel::kIsotropic; From e68db9399c76f207fccc166a1c67177695e7457b Mon Sep 17 00:00:00 2001 From: Tomoki Date: Fri, 17 Mar 2023 00:52:53 +0900 Subject: [PATCH 1039/1086] revert name of spacecraft_antenna and ground_station_antenna --- .../ground_station_calculator.cpp | 44 +++++++++---------- .../ground_station_calculator.hpp | 32 +++++++------- 2 files changed, 38 insertions(+), 38 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 685069833..26f4ec5d8 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -26,12 +26,12 @@ GroundStationCalculator::GroundStationCalculator(const double loss_polarization_ GroundStationCalculator::~GroundStationCalculator() {} -void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna) { +void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { bool is_visible = ground_station.IsVisible(spacecraft.GetSpacecraftId()); if (is_visible) { - max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_antenna, ground_station, ground_station_antenna); - receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_antenna, ground_station, ground_station_antenna); + max_bitrate_Mbps_ = CalcMaxBitrate(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); + receive_margin_dB_ = CalcReceiveMarginOnGs(spacecraft.GetDynamics(), spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); } else { max_bitrate_Mbps_ = 0.0; receive_margin_dB_ = -10000.0; // FIXME: which value is suitable? @@ -39,9 +39,9 @@ void GroundStationCalculator::Update(const Spacecraft& spacecraft, const Antenna } // Private functions -double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna) { - double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); +double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { + double cn0_dBHz = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); double margin_for_bitrate_dB = cn0_dBHz - (ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_) - margin_requirement_dB_; @@ -52,25 +52,25 @@ double GroundStationCalculator::CalcMaxBitrate(const Dynamics& dynamics, const A } } -double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, - const GroundStation& ground_station, const Antenna& ground_station_antenna) { - double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_antenna, ground_station, ground_station_antenna); - double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(spacecraft_antenna.GetBitrate_bps()); +double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, + const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { + double cn0_dB = CalcCn0OnGs(dynamics, spacecraft_tx_antenna, ground_station, ground_station_rx_antenna); + double cn0_requirement_dB = ebn0_dB_ + hardware_deterioration_dB_ + coding_gain_dB_ + 10.0 * log10(spacecraft_tx_antenna.GetBitrate_bps()); return cn0_dB - cn0_requirement_dB; } -double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna) { +double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna) { // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); double dist_sc_gs_km = CalcNorm(sc_pos_i - gs_pos_i) / 1000.0; - double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_antenna.GetFrequency_MHz() / 1000.0)); + double loss_space_dB = -20.0 * log10(4.0 * libra::pi * dist_sc_gs_km / (300.0 / spacecraft_tx_antenna.GetFrequency_MHz() / 1000.0)); // GS direction on SC TX antenna frame Vector<3> sc_to_gs_i = gs_pos_i - sc_pos_i; sc_to_gs_i = libra::Normalize(sc_to_gs_i); - Quaternion q_i_to_sc_ant = spacecraft_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); + Quaternion q_i_to_sc_ant = spacecraft_tx_antenna.GetQuaternion_b2c() * dynamics.GetAttitude().GetQuaternion_i2b(); Vector<3> gs_direction_on_sc_frame = q_i_to_sc_ant.FrameConversion(sc_to_gs_i); double theta_on_sc_antenna_rad = acos(gs_direction_on_sc_frame[2]); double phi_on_sc_antenna_rad = atan2(gs_direction_on_sc_frame[1], gs_direction_on_sc_frame[0]); @@ -78,23 +78,23 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante // SC direction on GS RX antenna frame Vector<3> gs_to_sc_ecef = dynamics.GetOrbit().GetPosition_ecef_m() - ground_station.GetPosition_ecef_m(); gs_to_sc_ecef = libra::Normalize(gs_to_sc_ecef); - Quaternion q_ecef_to_gs_ant = ground_station_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); + Quaternion q_ecef_to_gs_ant = ground_station_rx_antenna.GetQuaternion_b2c() * ground_station.GetGeodeticPosition().GetQuaternionXcxfToLtc(); Vector<3> sc_direction_on_gs_frame = q_ecef_to_gs_ant.FrameConversion(gs_to_sc_ecef); double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); double phi_on_gs_antenna_rad = atan2(sc_direction_on_gs_frame[1], sc_direction_on_gs_frame[0]); - if (spacecraft_antenna.IsTransmitter()) { + if (spacecraft_tx_antenna.IsTransmitter()) { // Calc CN0 - double cn0_dBHz = spacecraft_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + double cn0_dBHz = spacecraft_tx_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - ground_station_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + ground_station_rx_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } else { // Calc CN0 - double cn0_dBHz = ground_station_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + loss_polarization_dB_ + - loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - spacecraft_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - + double cn0_dBHz = ground_station_rx_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + + loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + + spacecraft_tx_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - 10.0 * log10(environment::boltzmann_constant_J_K); return cn0_dBHz; } diff --git a/src/components/real/communication/ground_station_calculator.hpp b/src/components/real/communication/ground_station_calculator.hpp index 284f54114..ab4ddb01b 100644 --- a/src/components/real/communication/ground_station_calculator.hpp +++ b/src/components/real/communication/ground_station_calculator.hpp @@ -45,12 +45,12 @@ class GroundStationCalculator : public ILoggable { * @fn Update * @brief Update maximum bitrate calculation * @param [in] spacecraft: Spacecraft information - * @param [in] spacecraft_antenna: Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_antenna: Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Antenna mounted on ground station */ - void Update(const Spacecraft& spacecraft, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna); + void Update(const Spacecraft& spacecraft, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); // Override ILoggable TODO: Maybe we don't need logabble, and this class should be used as library. /** @@ -104,36 +104,36 @@ class GroundStationCalculator : public ILoggable { * @fn CalcMaxBitrate * @brief Calculate the maximum bitrate * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return Max bitrate [Mbps] */ - double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna); + double CalcMaxBitrate(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); /** * @fn CalcReceiveMarginOnGs * @brief Calculate receive margin at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return Receive margin [dB] */ - double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna); + double CalcReceiveMarginOnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); /** * @fn CalcCn0 * @brief Calculate CN0 (Carrier to Noise density ratio) of received signal at the ground station * @param [in] dynamics: Spacecraft dynamics information - * @param [in] spacecraft_antenna: Tx Antenna mounted on spacecraft + * @param [in] spacecraft_tx_antenna: Tx Antenna mounted on spacecraft * @param [in] ground_station: Ground station information - * @param [in] ground_station_antenna: Rx Antenna mounted on ground station + * @param [in] ground_station_rx_antenna: Rx Antenna mounted on ground station * @return CN0 [dB] */ - double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_antenna, const GroundStation& ground_station, - const Antenna& ground_station_antenna); + double CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, + const Antenna& ground_station_rx_antenna); }; #endif // S2E_COMPONENTS_REAL_COMMUNICATION_GROUND_STATION_CALCULATOR_HPP_ From 55a508fee438e7fb94a512748baaff45f0c39a8b Mon Sep 17 00:00:00 2001 From: Tomoki Date: Fri, 17 Mar 2023 01:14:10 +0900 Subject: [PATCH 1040/1086] revert CalcCn0OnGs --- .../ground_station_calculator.cpp | 25 ++++++++----------- 1 file changed, 10 insertions(+), 15 deletions(-) diff --git a/src/components/real/communication/ground_station_calculator.cpp b/src/components/real/communication/ground_station_calculator.cpp index 26f4ec5d8..eef407331 100644 --- a/src/components/real/communication/ground_station_calculator.cpp +++ b/src/components/real/communication/ground_station_calculator.cpp @@ -61,6 +61,10 @@ double GroundStationCalculator::CalcReceiveMarginOnGs(const Dynamics& dynamics, double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Antenna& spacecraft_tx_antenna, const GroundStation& ground_station, const Antenna& ground_station_rx_antenna) { + if (!spacecraft_tx_antenna.IsTransmitter() || !ground_station_rx_antenna.IsReceiver()) { + // Check compatibility of transmitter and receiver + return 0.0f; + } // Free space path loss Vector<3> sc_pos_i = dynamics.GetOrbit().GetPosition_i_m(); Vector<3> gs_pos_i = ground_station.GetPosition_i_m(); @@ -83,21 +87,12 @@ double GroundStationCalculator::CalcCn0OnGs(const Dynamics& dynamics, const Ante double theta_on_gs_antenna_rad = acos(sc_direction_on_gs_frame[2]); double phi_on_gs_antenna_rad = atan2(sc_direction_on_gs_frame[1], sc_direction_on_gs_frame[0]); - if (spacecraft_tx_antenna.IsTransmitter()) { - // Calc CN0 - double cn0_dBHz = spacecraft_tx_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + - loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - ground_station_rx_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - - 10.0 * log10(environment::boltzmann_constant_J_K); - return cn0_dBHz; - } else { - // Calc CN0 - double cn0_dBHz = ground_station_rx_antenna.CalcTxEirp_dBW(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) + loss_space_dB + - loss_polarization_dB_ + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + - spacecraft_tx_antenna.CalcRxGt_dB_K(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) - - 10.0 * log10(environment::boltzmann_constant_J_K); - return cn0_dBHz; - } + // Calc CN0 + double cn0_dBHz = spacecraft_tx_antenna.CalcTxEirp_dBW(theta_on_sc_antenna_rad, phi_on_sc_antenna_rad) + loss_space_dB + loss_polarization_dB_ + + loss_atmosphere_dB_ + loss_rainfall_dB_ + loss_others_dB_ + + ground_station_rx_antenna.CalcRxGt_dB_K(theta_on_gs_antenna_rad, phi_on_gs_antenna_rad) - + 10.0 * log10(environment::boltzmann_constant_J_K); + return cn0_dBHz; } std::string GroundStationCalculator::GetLogHeader() const { From 1222b11646c210dd53c57835b5b65f106d640d9c Mon Sep 17 00:00:00 2001 From: Tomoki Date: Fri, 17 Mar 2023 01:24:40 +0900 Subject: [PATCH 1041/1086] rename the title --- src/simulation/ground_station/ground_station.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/simulation/ground_station/ground_station.cpp b/src/simulation/ground_station/ground_station.cpp index 63ba6ca55..f2ff97cb9 100644 --- a/src/simulation/ground_station/ground_station.cpp +++ b/src/simulation/ground_station/ground_station.cpp @@ -77,7 +77,7 @@ std::string GroundStation::GetLogHeader() const { std::string legend = head + "sc" + std::to_string(i) + "_visible_flag"; str_tmp += WriteScalar(legend); } - str_tmp += WriteVector("gs_pos", "eci", "m", 3); + str_tmp += WriteVector("ground_station_position", "eci", "m", 3); return str_tmp; } From dd553303630d90e3a73f9441e97a2349b56d0e60 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Mar 2023 11:50:59 +0100 Subject: [PATCH 1042/1086] Rename InitGeoPotential to InitGeopotential --- src/disturbances/disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.cpp | 2 +- src/disturbances/initialize_disturbances.hpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/disturbances/disturbances.cpp b/src/disturbances/disturbances.cpp index bce073cd8..59b1d8e67 100644 --- a/src/disturbances/disturbances.cpp +++ b/src/disturbances/disturbances.cpp @@ -88,7 +88,7 @@ void Disturbances::InitializeInstances(const SimulationConfiguration* simulation MagneticDisturbance* mag_dist = new MagneticDisturbance(InitMagneticDisturbance(initialize_file_name_, structure->GetResidualMagneticMoment())); disturbances_list_.push_back(mag_dist); - Geopotential* geopotential = new Geopotential(InitGeoPotential(initialize_file_name_)); + Geopotential* geopotential = new Geopotential(InitGeopotential(initialize_file_name_)); acceleration_disturbances_list_.push_back(geopotential); } diff --git a/src/disturbances/initialize_disturbances.cpp b/src/disturbances/initialize_disturbances.cpp index f233137fa..2f27603d6 100644 --- a/src/disturbances/initialize_disturbances.cpp +++ b/src/disturbances/initialize_disturbances.cpp @@ -74,7 +74,7 @@ MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_pa return mag_disturbance; } -Geopotential InitGeoPotential(const std::string initialize_file_path) { +Geopotential InitGeopotential(const std::string initialize_file_path) { auto conf = IniAccess(initialize_file_path); const char* section = "GEOPOTENTIAL"; diff --git a/src/disturbances/initialize_disturbances.hpp b/src/disturbances/initialize_disturbances.hpp index 3183a55f0..39face859 100644 --- a/src/disturbances/initialize_disturbances.hpp +++ b/src/disturbances/initialize_disturbances.hpp @@ -56,11 +56,11 @@ GravityGradient InitGravityGradient(const std::string initialize_file_path, cons MagneticDisturbance InitMagneticDisturbance(const std::string initialize_file_path, const ResidualMagneticMoment& rmm_params); /** - * @fn InitGeoPotential + * @fn InitGeopotential * @brief Initialize Geopotential class with earth gravitational constant * @param [in] initialize_file_path: Initialize file path */ -Geopotential InitGeoPotential(const std::string initialize_file_path); +Geopotential InitGeopotential(const std::string initialize_file_path); /** * @fn InitThirdBodyGravity From 575e8be9bafe361ba4c14f166e072ab7214765c7 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Mar 2023 13:12:32 +0100 Subject: [PATCH 1043/1086] Fix function name in test --- src/library/math/test_vector.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/library/math/test_vector.cpp b/src/library/math/test_vector.cpp index f8dd44f6e..9affb0fba 100644 --- a/src/library/math/test_vector.cpp +++ b/src/library/math/test_vector.cpp @@ -158,7 +158,7 @@ TEST(Vector, FillUp) { } double fill_up_value = 0.1; - FillUp(v, fill_up_value); + v.FillUp(fill_up_value); for (size_t i = 0; i < N; i++) { EXPECT_DOUBLE_EQ(fill_up_value, v[i]); @@ -349,7 +349,7 @@ TEST(Vector, CalcNorm) { const size_t N = 10; libra::Vector v(1.0); - double norm = CalcNorm(v); + double norm = v.CalcNorm(); // Check nondestructive for (size_t i = 0; i < N; i++) { @@ -366,11 +366,11 @@ TEST(Vector, Normalize) { const size_t N = 5; libra::Vector v(1.0); - libra::Vector normalized = Normalize(v); + libra::Vector normalized = v.CalcNormalizedVector(); for (size_t i = 0; i < N; i++) { - // Check nondestructive (Currently, it is destructive) - EXPECT_DOUBLE_EQ(1.0 / sqrt(double(N)), v[i]); + // Check nondestructive + EXPECT_DOUBLE_EQ(1.0, v[i]); // Check nondestructive EXPECT_DOUBLE_EQ(1.0 / sqrt(double(N)), normalized[i]); } From 60874e0784ccd21a4609a199d56358465a56a44f Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 17 Mar 2023 13:20:29 +0100 Subject: [PATCH 1044/1086] Fix function names in test --- src/library/math/test_matrix.cpp | 39 +++----------------------------- 1 file changed, 3 insertions(+), 36 deletions(-) diff --git a/src/library/math/test_matrix.cpp b/src/library/math/test_matrix.cpp index 0f18b2238..87080d601 100644 --- a/src/library/math/test_matrix.cpp +++ b/src/library/math/test_matrix.cpp @@ -154,7 +154,7 @@ TEST(Matrix, FillUp) { libra::Matrix m; - FillUp(m, value); + m.FillUp(value); for (size_t r = 0; r < R; r++) { for (size_t c = 0; c < C; c++) { @@ -177,7 +177,7 @@ TEST(Matrix, CalcTrace) { } } - double trace = CalcTrace(m); + double trace = m.CalcTrace(); // Check nondestructive for (size_t r = 0; r < N; r++) { @@ -326,7 +326,7 @@ TEST(Matrix, Transpose) { } } - libra::Matrix transposed = Transpose(m); + libra::Matrix transposed = m.Transpose(); for (size_t r = 0; r < R; r++) { for (size_t c = 0; c < C; c++) { @@ -338,39 +338,6 @@ TEST(Matrix, Transpose) { } } -/** - * @brief Test for Unitalize - */ -TEST(Matrix, Unitalize) { - const size_t N = 6; - - libra::Matrix m; - for (size_t r = 0; r < N; r++) { - for (size_t c = 0; c < N; c++) { - m[r][c] = r * c; - } - } - - libra::Matrix unitalized = Unitalize(m); - - for (size_t r = 0; r < N; r++) { - for (size_t c = 0; c < N; c++) { - // Check nondestructive (Currently, this is destructive) - if (r == c) { - EXPECT_DOUBLE_EQ(1.0, m[r][c]); - } else { - EXPECT_DOUBLE_EQ(0.0, m[r][c]); - } - // Check result - if (r == c) { - EXPECT_DOUBLE_EQ(1.0, unitalized[r][c]); - } else { - EXPECT_DOUBLE_EQ(0.0, unitalized[r][c]); - } - } - } -} - /** * @brief Test for MakeIdentityMatrix */ From ad5e6dae3489f3e27baee83b6de9365506650d96 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sun, 19 Mar 2023 10:56:16 +0100 Subject: [PATCH 1045/1086] Fix comment --- src/disturbances/disturbance.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/disturbances/disturbance.hpp b/src/disturbances/disturbance.hpp index bea7798a1..f43285374 100644 --- a/src/disturbances/disturbance.hpp +++ b/src/disturbances/disturbance.hpp @@ -77,7 +77,7 @@ class Disturbance : public ILoggable { */ virtual inline libra::Vector<3> GetAcceleration_i_m_s2() { return acceleration_i_m_s2_; } /** - * @fn GetAcceleration_i_m_s2 + * @fn IsAttitudeDependent * @brief Return the attitude dependent flag */ virtual inline bool IsAttitudeDependent() { return is_attitude_dependent_; } From d268697575e200565482d0724532cae5f1d7e2d9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 10:46:37 +0100 Subject: [PATCH 1046/1086] Replace char to string to remove strcpy warnings --- src/environment/global/celestial_information.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 24f578eba..4d3277995 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -182,16 +182,15 @@ std::string CelestialInformation::GetLogValue() const { void CelestialInformation::GetPlanetOrbit(const char* planet_name, const double et, double orbit[6]) { // Add `BARYCENTER` if needed const int kMaxNameLength = 100; - char planet_name_[kMaxNameLength]; - strcpy(planet_name_, planet_name); + std::string planet_name_string = planet_name; if (strcmp(planet_name, "MARS") == 0 || strcmp(planet_name, "JUPITER") == 0 || strcmp(planet_name, "SATURN") == 0 || strcmp(planet_name, "URANUS") == 0 || strcmp(planet_name, "NEPTUNE") == 0 || strcmp(planet_name, "PLUTO") == 0) { - strcat(planet_name_, "_BARYCENTER"); + planet_name_string += "_BARYCENTER"; } // Get orbit SpiceDouble lt; - spkezr_c((ConstSpiceChar*)planet_name_, (SpiceDouble)et, (ConstSpiceChar*)inertial_frame_name_.c_str(), + spkezr_c((ConstSpiceChar*)planet_name_string.c_str(), (SpiceDouble)et, (ConstSpiceChar*)inertial_frame_name_.c_str(), (ConstSpiceChar*)aberration_correction_setting_.c_str(), (ConstSpiceChar*)center_body_name_.c_str(), (SpiceDouble*)orbit, (SpiceDouble*)<); return; From 2163920d582244a5cc97c98209815b084e75bba5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 10:53:23 +0100 Subject: [PATCH 1047/1086] Add const to use the same arguments with orverride functions --- src/dynamics/orbit/kepler_orbit_propagation.hpp | 2 +- src/dynamics/orbit/relative_orbit.hpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/dynamics/orbit/kepler_orbit_propagation.hpp b/src/dynamics/orbit/kepler_orbit_propagation.hpp index 3a7122a8d..bed2bf624 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.hpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.hpp @@ -37,7 +37,7 @@ class KeplerOrbitPropagation : public Orbit, public KeplerOrbit { * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd); + virtual void Propagate(const double end_time_s, const double current_time_jd); private: /** diff --git a/src/dynamics/orbit/relative_orbit.hpp b/src/dynamics/orbit/relative_orbit.hpp index bb7562622..09b8d1403 100644 --- a/src/dynamics/orbit/relative_orbit.hpp +++ b/src/dynamics/orbit/relative_orbit.hpp @@ -55,7 +55,7 @@ class RelativeOrbit : public Orbit, public libra::OrdinaryDifferentialEquation<6 * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd); + virtual void Propagate(const double end_time_s, const double current_time_jd); // Override OrdinaryDifferentialEquation /** diff --git a/src/dynamics/orbit/rk4_orbit_propagation.hpp b/src/dynamics/orbit/rk4_orbit_propagation.hpp index fb363146e..bdb98b808 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.hpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.hpp @@ -52,7 +52,7 @@ class Rk4OrbitPropagation : public Orbit, public libra::OrdinaryDifferentialEqua * @param [in] end_time_s: End time of simulation [sec] * @param [in] current_time_jd: Current Julian day [day] */ - virtual void Propagate(double end_time_s, double current_time_jd); + virtual void Propagate(const double end_time_s, const double current_time_jd); private: double gravity_constant_m3_s2_; //!< Gravity constant [m3/s2] From d3a08973b39c42f7a78dab51e78261c834bb46de Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 10:59:34 +0100 Subject: [PATCH 1048/1086] Add const to use the same arguments with orverride functions --- src/dynamics/orbit/encke_orbit_propagation.cpp | 2 +- src/dynamics/orbit/kepler_orbit_propagation.cpp | 2 +- src/dynamics/orbit/relative_orbit.cpp | 2 +- src/dynamics/orbit/rk4_orbit_propagation.cpp | 2 +- src/dynamics/orbit/sgp4_orbit_propagation.cpp | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/dynamics/orbit/encke_orbit_propagation.cpp b/src/dynamics/orbit/encke_orbit_propagation.cpp index 4f8c4fbde..941665edf 100644 --- a/src/dynamics/orbit/encke_orbit_propagation.cpp +++ b/src/dynamics/orbit/encke_orbit_propagation.cpp @@ -24,7 +24,7 @@ EnckeOrbitPropagation::EnckeOrbitPropagation(const CelestialInformation* celesti EnckeOrbitPropagation::~EnckeOrbitPropagation() {} // Functions for Orbit -void EnckeOrbitPropagation::Propagate(double end_time_s, double current_time_jd) { +void EnckeOrbitPropagation::Propagate(const double end_time_s, const double current_time_jd) { if (!is_calc_enabled_) return; // Rectification diff --git a/src/dynamics/orbit/kepler_orbit_propagation.cpp b/src/dynamics/orbit/kepler_orbit_propagation.cpp index 1137b7e1c..776c468d2 100644 --- a/src/dynamics/orbit/kepler_orbit_propagation.cpp +++ b/src/dynamics/orbit/kepler_orbit_propagation.cpp @@ -16,7 +16,7 @@ KeplerOrbitPropagation::KeplerOrbitPropagation(const CelestialInformation* celes KeplerOrbitPropagation::~KeplerOrbitPropagation() {} -void KeplerOrbitPropagation::Propagate(double end_time_s, double current_time_jd) { +void KeplerOrbitPropagation::Propagate(const double end_time_s, const double current_time_jd) { UNUSED(end_time_s); if (!is_calc_enabled_) return; diff --git a/src/dynamics/orbit/relative_orbit.cpp b/src/dynamics/orbit/relative_orbit.cpp index 92e82184d..347e07e87 100644 --- a/src/dynamics/orbit/relative_orbit.cpp +++ b/src/dynamics/orbit/relative_orbit.cpp @@ -94,7 +94,7 @@ void RelativeOrbit::CalculateStm(StmModel stm_model_type, const Orbit* reference } } -void RelativeOrbit::Propagate(double end_time_s, double current_time_jd) { +void RelativeOrbit::Propagate(const double end_time_s, const double current_time_jd) { UNUSED(current_time_jd); if (!is_calc_enabled_) return; diff --git a/src/dynamics/orbit/rk4_orbit_propagation.cpp b/src/dynamics/orbit/rk4_orbit_propagation.cpp index 545e6e7d5..683db283b 100644 --- a/src/dynamics/orbit/rk4_orbit_propagation.cpp +++ b/src/dynamics/orbit/rk4_orbit_propagation.cpp @@ -62,7 +62,7 @@ void Rk4OrbitPropagation::Initialize(libra::Vector<3> position_i_m, libra::Vecto TransformEcefToGeodetic(); } -void Rk4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { +void Rk4OrbitPropagation::Propagate(const double end_time_s, const double current_time_jd) { UNUSED(current_time_jd); if (!is_calc_enabled_) return; diff --git a/src/dynamics/orbit/sgp4_orbit_propagation.cpp b/src/dynamics/orbit/sgp4_orbit_propagation.cpp index b4c741857..e79bcfc2a 100644 --- a/src/dynamics/orbit/sgp4_orbit_propagation.cpp +++ b/src/dynamics/orbit/sgp4_orbit_propagation.cpp @@ -35,7 +35,7 @@ Sgp4OrbitPropagation::Sgp4OrbitPropagation(const CelestialInformation* celestial is_calc_enabled_ = false; } -void Sgp4OrbitPropagation::Propagate(double end_time_s, double current_time_jd) { +void Sgp4OrbitPropagation::Propagate(const double end_time_s, const double current_time_jd) { UNUSED(end_time_s); if (!is_calc_enabled_) return; From 4079920af656c85b70de9067dc2823f936371b4b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 10:59:38 +0100 Subject: [PATCH 1049/1086] Add const to use the same arguments with orverride functions --- .../examples/example_serial_communication_with_obc.cpp | 2 +- .../examples/example_serial_communication_with_obc.hpp | 2 +- src/components/real/cdh/on_board_computer.hpp | 2 +- src/components/real/mission/telescope.cpp | 4 ++-- src/components/real/mission/telescope.hpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/components/examples/example_serial_communication_with_obc.cpp b/src/components/examples/example_serial_communication_with_obc.cpp index e79468825..c5b6f83de 100644 --- a/src/components/examples/example_serial_communication_with_obc.cpp +++ b/src/components/examples/example_serial_communication_with_obc.cpp @@ -51,6 +51,6 @@ void ExampleSerialCommunicationWithObc::MainRoutine(const int time_count) { SendTelemetry(0); } -void ExampleSerialCommunicationWithObc::GpioStateChanged(int port_id, bool is_positive_edge) { +void ExampleSerialCommunicationWithObc::GpioStateChanged(const int port_id, const bool is_positive_edge) { printf("interrupted. portid = %d, isPosedge = %d./n", port_id, is_positive_edge); } diff --git a/src/components/examples/example_serial_communication_with_obc.hpp b/src/components/examples/example_serial_communication_with_obc.hpp index 89bcee035..b52dc9672 100644 --- a/src/components/examples/example_serial_communication_with_obc.hpp +++ b/src/components/examples/example_serial_communication_with_obc.hpp @@ -64,7 +64,7 @@ class ExampleSerialCommunicationWithObc : public Component, public UartCommunica * @fn GpioStateChanged * @brief Interrupt function for GPIO */ - void GpioStateChanged(int port_id, bool is_positive_edge); + void GpioStateChanged(const int port_id, const bool is_positive_edge); private: const static int kMaxMemoryLength = 100; //!< Maximum memory length diff --git a/src/components/real/cdh/on_board_computer.hpp b/src/components/real/cdh/on_board_computer.hpp index a56f37715..641f1566c 100644 --- a/src/components/real/cdh/on_board_computer.hpp +++ b/src/components/real/cdh/on_board_computer.hpp @@ -199,7 +199,7 @@ class OnBoardComputer : public Component { * @brief Main routine to execute flight software * @note Users need to write flight software */ - virtual void MainRoutine(int time_count); + virtual void MainRoutine(const int time_count); private: std::map uart_ports_; //!< UART ports diff --git a/src/components/real/mission/telescope.cpp b/src/components/real/mission/telescope.cpp index cc8c80e64..f36603ad7 100644 --- a/src/components/real/mission/telescope.cpp +++ b/src/components/real/mission/telescope.cpp @@ -56,8 +56,8 @@ Telescope::Telescope(ClockGenerator* clock_generator, const libra::Quaternion& q Telescope::~Telescope() {} -void Telescope::MainRoutine(int count) { - UNUSED(count); +void Telescope::MainRoutine(const int time_count) { + UNUSED(time_count); // Check forbidden angle is_sun_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("SUN"), sun_forbidden_angle_rad_); is_earth_in_forbidden_angle = JudgeForbiddenAngle(local_celestial_information_->GetPositionFromSpacecraft_b_m("EARTH"), earth_forbidden_angle_rad_); diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index cd66778a4..7dd89ea81 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -103,7 +103,7 @@ class Telescope : public Component, public ILoggable { * @fn MainRoutine * @brief Main routine to calculate force generation */ - void MainRoutine(int count); + void MainRoutine(const int time_count); /** * @fn Observe From e8c32401638c2dd1e618ceedf007ae4c76d7493e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 11:13:53 +0100 Subject: [PATCH 1050/1086] Remove unnecessary variable --- src/environment/global/celestial_information.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 4d3277995..0f86f895f 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -181,7 +181,6 @@ std::string CelestialInformation::GetLogValue() const { void CelestialInformation::GetPlanetOrbit(const char* planet_name, const double et, double orbit[6]) { // Add `BARYCENTER` if needed - const int kMaxNameLength = 100; std::string planet_name_string = planet_name; if (strcmp(planet_name, "MARS") == 0 || strcmp(planet_name, "JUPITER") == 0 || strcmp(planet_name, "SATURN") == 0 || strcmp(planet_name, "URANUS") == 0 || strcmp(planet_name, "NEPTUNE") == 0 || strcmp(planet_name, "PLUTO") == 0) { From bd7bd3d7ba4352f0d75c7ff6f3861df4fceee51b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 11:29:55 +0100 Subject: [PATCH 1051/1086] Fix warnings in lower case transformation --- src/environment/global/celestial_information.cpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 0f86f895f..45d47bfcb 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -156,7 +156,7 @@ std::string CelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, kMaxNameLength, name_buffer, (SpiceBoolean*)&found); std::string name = name_buffer; - std::transform(name.begin(), name.end(), name.begin(), ::tolower); + std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return std::tolower(c); }); std::string body_pos = name + "_position"; std::string body_vel = name + "_velocity"; diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 82398aa4a..adf7f6c23 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -172,7 +172,7 @@ std::string LocalCelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); std::string name = namebuf; - std::transform(name.begin(), name.end(), name.begin(), ::tolower); + std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return std::tolower(c); }); std::string body_pos = name + "_position_from_spacecraft"; std::string body_vel = name + "_velocity_from_spacecraft"; str_tmp += WriteVector(body_pos, "b", "m", 3); From f2b83bf9c4250481a1950cdce9ae1a84982d0f53 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 12:47:15 +0100 Subject: [PATCH 1052/1086] Add cast to char --- src/environment/global/celestial_information.cpp | 2 +- src/environment/local/local_celestial_information.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 45d47bfcb..73b0a9c56 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -156,7 +156,7 @@ std::string CelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, kMaxNameLength, name_buffer, (SpiceBoolean*)&found); std::string name = name_buffer; - std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return std::tolower(c); }); + std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return (char)std::tolower(c); }); std::string body_pos = name + "_position"; std::string body_vel = name + "_velocity"; diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index adf7f6c23..4f31300b2 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -172,7 +172,7 @@ std::string LocalCelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); std::string name = namebuf; - std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return std::tolower(c); }); + std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return (char)std::tolower(c); }); std::string body_pos = name + "_position_from_spacecraft"; std::string body_vel = name + "_velocity_from_spacecraft"; str_tmp += WriteVector(body_pos, "b", "m", 3); From 628d69cb296ad9f4c6fb8334eb9cb4674426416b Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 14:51:31 +0100 Subject: [PATCH 1053/1086] Fix Info to Information --- src/environment/global/celestial_information.cpp | 2 +- src/environment/global/celestial_information.hpp | 4 ++-- src/environment/global/global_environment.cpp | 4 ++-- src/environment/local/local_celestial_information.hpp | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 24f578eba..8c44b7e92 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -100,7 +100,7 @@ CelestialInformation::~CelestialInformation() { delete earth_rotation_; } -void CelestialInformation::UpdateAllObjectsInfo(const double current_time_jd) { +void CelestialInformation::UpdateAllObjectsInformation(const double current_time_jd) { // Convert time SpiceDouble ephemeris_time; std::string julian_date = "jd " + std::to_string(current_time_jd); diff --git a/src/environment/global/celestial_information.hpp b/src/environment/global/celestial_information.hpp index d2aeb4e24..96286bf6a 100644 --- a/src/environment/global/celestial_information.hpp +++ b/src/environment/global/celestial_information.hpp @@ -54,11 +54,11 @@ class CelestialInformation : public ILoggable { virtual std::string GetLogValue() const; /** - * @fn UpdateAllObjectsInfo + * @fn UpdateAllObjectsInformation * @brief Update the information of all selected celestial objects * @param [in] current_time_jd: Current time [Julian day] */ - void UpdateAllObjectsInfo(const double current_time_jd); + void UpdateAllObjectsInformation(const double current_time_jd); // Getters // Orbit information diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 0665bca72..9e63c7b9f 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -30,13 +30,13 @@ void GlobalEnvironment::Initialize(SimulationConfiguration* simulation_configura gnss_satellites_ = InitGnssSatellites(simulation_configuration->gnss_file_); // Calc initial value - celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentTime_jd()); + celestial_information_->UpdateAllObjectsInformation(simulation_time_->GetCurrentTime_jd()); gnss_satellites_->SetUp(simulation_time_); } void GlobalEnvironment::Update() { simulation_time_->UpdateTime(); - celestial_information_->UpdateAllObjectsInfo(simulation_time_->GetCurrentTime_jd()); + celestial_information_->UpdateAllObjectsInformation(simulation_time_->GetCurrentTime_jd()); gnss_satellites_->Update(simulation_time_); } diff --git a/src/environment/local/local_celestial_information.hpp b/src/environment/local/local_celestial_information.hpp index 30f67942f..5d21b7da1 100644 --- a/src/environment/local/local_celestial_information.hpp +++ b/src/environment/local/local_celestial_information.hpp @@ -27,7 +27,7 @@ class LocalCelestialInformation : public ILoggable { virtual ~LocalCelestialInformation(); /** - * @fn UpdateAllObjectsInfo + * @fn UpdateAllObjectsInformation * @brief Update the all selected celestial object local information * @param [in] spacecraft_position_from_center_i_m: Spacecraft position from the center body in the inertial frame [m] * @param [in] spacecraft_velocity_from_center_i_m_s: Spacecraft velocity from the center body in the inertial frame [m/s] From 4373c131b87e3764e6a0f1e492a741662b21b19c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 16:43:20 +0100 Subject: [PATCH 1054/1086] Fix comment --- src/simulation/case/sample_case.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index bde34effc..3fc0fdf7f 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -16,7 +16,7 @@ SampleCase::~SampleCase() { delete sample_spacecraft_; } void SampleCase::Initialize() { // Instantiate the target of the simulation - // `spacecraft_id` corresponds to the index of `sat_file` in Simbase.ini + // `spacecraft_id` corresponds to the index of `spacecraft_file` in simulation_base.ini const int spacecraft_id = 0; sample_spacecraft_ = new SampleSpacecraft(&simulation_configuration_, global_environment_, spacecraft_id); const int ground_station_id = 0; From c592765cff434b63be322fe6ab7282673b0d00b1 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 20 Mar 2023 16:45:32 +0100 Subject: [PATCH 1055/1086] Add delete ground station --- src/simulation/case/sample_case.cpp | 21 +++++---------------- 1 file changed, 5 insertions(+), 16 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index 3fc0fdf7f..c8a27a8c3 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -12,7 +12,10 @@ using std::string; SampleCase::SampleCase(string initialise_base_file) : SimulationCase(initialise_base_file) {} -SampleCase::~SampleCase() { delete sample_spacecraft_; } +SampleCase::~SampleCase() { + delete sample_spacecraft_; + delete sample_ground_station_; +} void SampleCase::Initialize() { // Instantiate the target of the simulation @@ -36,7 +39,7 @@ void SampleCase::Initialize() { } void SampleCase::Main() { - global_environment_->Reset(); // for MonteCarlo Sim + global_environment_->Reset(); // for MonteCarlo Simulation while (!global_environment_->GetSimulationTime().GetState().finish) { // Logging if (global_environment_->GetSimulationTime().GetState().log_output) { @@ -61,10 +64,6 @@ string SampleCase::GetLogHeader() const { string str_tmp = ""; str_tmp += WriteScalar("time", "s"); - // str_tmp += WriteVector("position", "i", "m", 3); - // str_tmp += WriteVector("velocity", "i", "m/s", 3); - // str_tmp += WriteVector("quaternion", "i2b", "-", 4); - // str_tmp += WriteVector("omega", "b", "-", 3); return str_tmp; } @@ -72,17 +71,7 @@ string SampleCase::GetLogHeader() const { string SampleCase::GetLogValue() const { string str_tmp = ""; - // auto pos_i = sample_sat->dynamics_->GetOrbit().GetPosition_i_m(); - // auto vel_i = sample_sat->dynamics_->GetOrbit().GetVelocity_i_m_s(); - // auto quat_i2b = sample_sat->dynamics_->GetAttitude().GetQuaternion_i2b(); - // auto omega_b = sample_sat->dynamics_->GetAttitude().GetAngularVelocity_b_rad_s(); - - // Need to match the contents of log with header setting above str_tmp += WriteScalar(global_environment_->GetSimulationTime().GetElapsedTime_s()); - // str_tmp += WriteVector(pos_i, 16); - // str_tmp += WriteVector(vel_i, 10); - // str_tmp += WriteQuaternion(quat_i2b); - // str_tmp += WriteVector(omega_b, 10); return str_tmp; } From 76ddad84089c8faae8a3f9d1064fca047a2425ec Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 08:42:21 +0100 Subject: [PATCH 1056/1086] Fix comment --- src/simulation/ground_station/ground_station.hpp | 2 +- .../sample_ground_station/sample_ground_station.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 9847d0248..7b98e0d85 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -1,5 +1,5 @@ /** - * @file ground_station.h + * @file ground_station.hpp * @brief Base class of ground station */ diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp index 674bdc6ff..8b4006b4e 100644 --- a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp +++ b/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp @@ -1,5 +1,5 @@ /** - * @file sample_ground_station.h + * @file sample_ground_station.hpp * @brief An example of user defined ground station class */ From 58a2ba6587a95794d6c2e6beec293fd2983c289d Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 13:33:57 +0100 Subject: [PATCH 1057/1086] Fix magnetic field random walk standard deviation --- data/sample/initialize_files/sample_local_environment.ini | 2 +- src/environment/local/initialize_local_environment.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/data/sample/initialize_files/sample_local_environment.ini b/data/sample/initialize_files/sample_local_environment.ini index 06faad3bd..7d2703e7f 100644 --- a/data/sample/initialize_files/sample_local_environment.ini +++ b/data/sample/initialize_files/sample_local_environment.ini @@ -2,7 +2,7 @@ calculation = ENABLE logging = ENABLE coefficient_file = ../../../s2e-core/src/library/external/igrf/igrf13.coef -magnetic_field_random_walk_speed_nT = 10.0 +magnetic_field_random_walk_standard_deviation_nT = 10.0 magnetic_field_random_walk_limit_nT = 400.0 magnetic_field_white_noise_standard_deviation_nT = 50.0 diff --git a/src/environment/local/initialize_local_environment.cpp b/src/environment/local/initialize_local_environment.cpp index 0de817e30..07873709a 100644 --- a/src/environment/local/initialize_local_environment.cpp +++ b/src/environment/local/initialize_local_environment.cpp @@ -16,7 +16,7 @@ GeomagneticField InitGeomagneticField(std::string initialize_file_path) { const char* section = "MAGNETIC_FIELD_ENVIRONMENT"; std::string fname = conf.ReadString(section, "coefficient_file"); - double mag_rwdev = conf.ReadDouble(section, "magnetic_field_random_walk_speed_nT"); + double mag_rwdev = conf.ReadDouble(section, "magnetic_field_random_walk_standard_deviation_nT"); double mag_rwlimit = conf.ReadDouble(section, "magnetic_field_random_walk_limit_nT"); double mag_wnvar = conf.ReadDouble(section, "magnetic_field_white_noise_standard_deviation_nT"); From fb3ef88fbf66a217da9b6dc1aa9b759eade568c0 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:00:14 +0100 Subject: [PATCH 1058/1086] Fix comment --- src/simulation/case/sample_case.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 0e0e7110e..41bd354c0 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -12,7 +12,7 @@ /** * @class SampleCase - * @brief An example of user side spacecraft class + * @brief An example of user defined simulation class */ class SampleCase : public SimulationCase { public: From 969c6248395bf23060551a16d0e9630ef658d466 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:10:55 +0100 Subject: [PATCH 1059/1086] Add const --- src/environment/global/global_environment.cpp | 4 ++-- src/environment/global/global_environment.hpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/environment/global/global_environment.cpp b/src/environment/global/global_environment.cpp index 0665bca72..adf1741ac 100644 --- a/src/environment/global/global_environment.cpp +++ b/src/environment/global/global_environment.cpp @@ -9,7 +9,7 @@ #include "initialize_gnss_satellites.hpp" #include "library/initialize/initialize_file_access.hpp" -GlobalEnvironment::GlobalEnvironment(SimulationConfiguration* simulation_configuration) { Initialize(simulation_configuration); } +GlobalEnvironment::GlobalEnvironment(const SimulationConfiguration* simulation_configuration) { Initialize(simulation_configuration); } GlobalEnvironment::~GlobalEnvironment() { delete simulation_time_; @@ -18,7 +18,7 @@ GlobalEnvironment::~GlobalEnvironment() { delete gnss_satellites_; } -void GlobalEnvironment::Initialize(SimulationConfiguration* simulation_configuration) { +void GlobalEnvironment::Initialize(const SimulationConfiguration* simulation_configuration) { // Get ini file path IniAccess iniAccess = IniAccess(simulation_configuration->initialize_base_file_name_); std::string simulation_time_ini_path = simulation_configuration->initialize_base_file_name_; diff --git a/src/environment/global/global_environment.hpp b/src/environment/global/global_environment.hpp index 1076cebc7..58ec95aba 100644 --- a/src/environment/global/global_environment.hpp +++ b/src/environment/global/global_environment.hpp @@ -24,7 +24,7 @@ class GlobalEnvironment { * @brief Constructor * @param [in] simulation_configuration: Simulation configuration */ - GlobalEnvironment(SimulationConfiguration* simulation_configuration); + GlobalEnvironment(const SimulationConfiguration* simulation_configuration); /** * @fn ~GlobalEnvironment * @brief Destructor @@ -36,7 +36,7 @@ class GlobalEnvironment { * @brief Initialize all global environment members * @param [in] simulation_configuration: Simulation configuration */ - void Initialize(SimulationConfiguration* simulation_configuration); + void Initialize(const SimulationConfiguration* simulation_configuration); /** * @fn Update * @brief Update states of all global environment From 546964d325a6d7f9ddc6b9a02661332508d19e38 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:21:02 +0100 Subject: [PATCH 1060/1086] Integrate initialize process to one function --- src/simulation/case/simulation_case.cpp | 43 ++++++++++++++----------- src/simulation/case/simulation_case.hpp | 2 ++ 2 files changed, 26 insertions(+), 19 deletions(-) diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 0f87e82ba..7dee45de8 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -10,41 +10,46 @@ #include SimulationCase::SimulationCase(const std::string initialise_base_file) { - IniAccess simulation_base_ini = IniAccess(initialise_base_file); - const char* section = "SIMULATION_SETTINGS"; - simulation_configuration_.initialize_base_file_name_ = initialise_base_file; - simulation_configuration_.main_logger_ = InitLog(simulation_configuration_.initialize_base_file_name_); - simulation_configuration_.number_of_simulated_spacecraft_ = simulation_base_ini.ReadInt(section, "number_of_simulated_spacecraft"); - simulation_configuration_.spacecraft_file_list_ = simulation_base_ini.ReadStrVector(section, "spacecraft_file"); - - simulation_configuration_.number_of_simulated_ground_station_ = simulation_base_ini.ReadInt(section, "number_of_simulated_ground_station"); - simulation_configuration_.ground_station_file_list_ = simulation_base_ini.ReadStrVector(section, "ground_station_file"); + // Initialize Log + simulation_configuration_.main_logger_ = InitLog(initialise_base_file); - simulation_configuration_.inter_sc_communication_file_ = simulation_base_ini.ReadString(section, "inter_sat_comm_file"); - simulation_configuration_.gnss_file_ = simulation_base_ini.ReadString(section, "gnss_file"); - global_environment_ = new GlobalEnvironment(&simulation_configuration_); + // Initialize Simulation Configuration + InitializeSimulationConfiguration(initialise_base_file); } SimulationCase::SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { - IniAccess simulation_base_ini = IniAccess(initialise_base_file); - const char* section = "SIMULATION_SETTINGS"; - simulation_configuration_.initialize_base_file_name_ = initialise_base_file; + // Initialize Log // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; - // ToDo: Consider that `enable_inilog = false` is fine or not? + // TODO: Consider that `enable_inilog = false` is fine or not? simulation_configuration_.main_logger_ = new Logger(log_file_name, log_path, initialise_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); + + // Initialize Simulation Configuration + InitializeSimulationConfiguration(initialise_base_file); +} + +SimulationCase::~SimulationCase() { delete global_environment_; } + +void SimulationCase::InitializeSimulationConfiguration(const std::string initialise_base_file) { + // Initialize + IniAccess simulation_base_ini = IniAccess(initialise_base_file); + const char* section = "SIMULATION_SETTINGS"; + simulation_configuration_.initialize_base_file_name_ = initialise_base_file; + + // Spacecraft simulation_configuration_.number_of_simulated_spacecraft_ = simulation_base_ini.ReadInt(section, "number_of_simulated_spacecraft"); simulation_configuration_.spacecraft_file_list_ = simulation_base_ini.ReadStrVector(section, "spacecraft_file"); + // Ground Station simulation_configuration_.number_of_simulated_ground_station_ = simulation_base_ini.ReadInt(section, "number_of_simulated_ground_station"); simulation_configuration_.ground_station_file_list_ = simulation_base_ini.ReadStrVector(section, "ground_station_file"); + // Others simulation_configuration_.inter_sc_communication_file_ = simulation_base_ini.ReadString(section, "inter_sat_comm_file"); simulation_configuration_.gnss_file_ = simulation_base_ini.ReadString(section, "gnss_file"); + // Global Environment global_environment_ = new GlobalEnvironment(&simulation_configuration_); -} - -SimulationCase::~SimulationCase() { delete global_environment_; } +} \ No newline at end of file diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index fe2f468d1..70a9020de 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -73,6 +73,8 @@ class SimulationCase : public ILoggable { protected: SimulationConfiguration simulation_configuration_; //!< Simulation setting GlobalEnvironment* global_environment_; //!< Global Environment + + void InitializeSimulationConfiguration(const std::string initialise_base_file); }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From aadb545eac5003c37b92ac3a2e9fe6e35cf0c145 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:22:54 +0100 Subject: [PATCH 1061/1086] Add comment and fix typo --- src/simulation/case/simulation_case.cpp | 18 +++++++++--------- src/simulation/case/simulation_case.hpp | 11 ++++++++--- 2 files changed, 17 insertions(+), 12 deletions(-) diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 7dee45de8..9cdc1b439 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -9,34 +9,34 @@ #include #include -SimulationCase::SimulationCase(const std::string initialise_base_file) { +SimulationCase::SimulationCase(const std::string initialize_base_file) { // Initialize Log - simulation_configuration_.main_logger_ = InitLog(initialise_base_file); + simulation_configuration_.main_logger_ = InitLog(initialize_base_file); // Initialize Simulation Configuration - InitializeSimulationConfiguration(initialise_base_file); + InitializeSimulationConfiguration(initialize_base_file); } -SimulationCase::SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, +SimulationCase::SimulationCase(const std::string initialize_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { // Initialize Log // Log for Monte Carlo Simulation std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; // TODO: Consider that `enable_inilog = false` is fine or not? simulation_configuration_.main_logger_ = - new Logger(log_file_name, log_path, initialise_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); + new Logger(log_file_name, log_path, initialize_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); // Initialize Simulation Configuration - InitializeSimulationConfiguration(initialise_base_file); + InitializeSimulationConfiguration(initialize_base_file); } SimulationCase::~SimulationCase() { delete global_environment_; } -void SimulationCase::InitializeSimulationConfiguration(const std::string initialise_base_file) { +void SimulationCase::InitializeSimulationConfiguration(const std::string initialize_base_file) { // Initialize - IniAccess simulation_base_ini = IniAccess(initialise_base_file); + IniAccess simulation_base_ini = IniAccess(initialize_base_file); const char* section = "SIMULATION_SETTINGS"; - simulation_configuration_.initialize_base_file_name_ = initialise_base_file; + simulation_configuration_.initialize_base_file_name_ = initialize_base_file; // Spacecraft simulation_configuration_.number_of_simulated_spacecraft_ = simulation_base_ini.ReadInt(section, "number_of_simulated_spacecraft"); diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 70a9020de..874101611 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -23,12 +23,12 @@ class SimulationCase : public ILoggable { * @fn SimulationCase * @brief Constructor */ - SimulationCase(const std::string initialise_base_file); + SimulationCase(const std::string initialize_base_file); /** * @fn SimulationCase * @brief Constructor for Monte-Carlo Simulation */ - SimulationCase(const std::string initialise_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path); + SimulationCase(const std::string initialize_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path); /** * @fn ~SimulationCase * @brief Destructor @@ -74,7 +74,12 @@ class SimulationCase : public ILoggable { SimulationConfiguration simulation_configuration_; //!< Simulation setting GlobalEnvironment* global_environment_; //!< Global Environment - void InitializeSimulationConfiguration(const std::string initialise_base_file); + /** + * @fn GetGlobalEnvironment + * @brief Return global environment + * @param[in] initialize_base_file: File path to initialize base file + */ + void InitializeSimulationConfiguration(const std::string initialize_base_file); }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From a50a4a34fb3b22263dd26880a6d569586c8eb4c9 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:24:26 +0100 Subject: [PATCH 1062/1086] Change pure virtual function to a virtual function --- src/simulation/case/simulation_case.cpp | 12 ++++++++++++ src/simulation/case/simulation_case.hpp | 4 ++-- 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 9cdc1b439..c7f9e72cc 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -32,6 +32,18 @@ SimulationCase::SimulationCase(const std::string initialize_base_file, const Mon SimulationCase::~SimulationCase() { delete global_environment_; } +std::string SimulationCase::GetLogHeader() const { + std::string str_tmp = ""; + + return str_tmp; +} + +std::string SimulationCase::GetLogValue() const { + std::string str_tmp = ""; + + return str_tmp; +} + void SimulationCase::InitializeSimulationConfiguration(const std::string initialize_base_file) { // Initialize IniAccess simulation_base_ini = IniAccess(initialize_base_file); diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 874101611..8998ca24d 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -51,12 +51,12 @@ class SimulationCase : public ILoggable { * @fn GetLogHeader * @brief Virtual function of Log header settings for Monte-Carlo Simulation result */ - virtual std::string GetLogHeader() const = 0; + virtual std::string GetLogHeader() const; /** * @fn GetLogValue * @brief Virtual function of Log value settings for Monte-Carlo Simulation result */ - virtual std::string GetLogValue() const = 0; + virtual std::string GetLogValue() const; // Getter /** From 010404a04aeb08e404b01632682de84a72ca9454 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:32:56 +0100 Subject: [PATCH 1063/1086] Separate Initialize function to general part and user defined part to simplify the user codes --- src/simulation/case/sample_case.cpp | 10 +--------- src/simulation/case/sample_case.hpp | 12 ++++++------ src/simulation/case/simulation_case.cpp | 12 ++++++++++++ src/simulation/case/simulation_case.hpp | 17 ++++++++++++++--- 4 files changed, 33 insertions(+), 18 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index c8a27a8c3..b87e821a1 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -17,7 +17,7 @@ SampleCase::~SampleCase() { delete sample_ground_station_; } -void SampleCase::Initialize() { +void SampleCase::InitializeTargetObjects() { // Instantiate the target of the simulation // `spacecraft_id` corresponds to the index of `spacecraft_file` in simulation_base.ini const int spacecraft_id = 0; @@ -26,16 +26,8 @@ void SampleCase::Initialize() { sample_ground_station_ = new SampleGroundStation(&simulation_configuration_, ground_station_id); // Register the log output - global_environment_->LogSetup(*(simulation_configuration_.main_logger_)); sample_spacecraft_->LogSetup(*(simulation_configuration_.main_logger_)); sample_ground_station_->LogSetup(*(simulation_configuration_.main_logger_)); - - // Write headers to the log - simulation_configuration_.main_logger_->WriteHeaders(); - - // Start the simulation - cout << "\nSimulationDateTime \n"; - global_environment_->GetSimulationTime().PrintStartDateTime(); } void SampleCase::Main() { diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 41bd354c0..051883fb6 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -28,12 +28,6 @@ class SampleCase : public SimulationCase { */ virtual ~SampleCase(); - /** - * @fn Initialize - * @brief Override function of Initialize in SimulationCase - */ - void Initialize(); - /** * @fn Main * @brief Override function of Main in SimulationCase @@ -54,6 +48,12 @@ class SampleCase : public SimulationCase { private: SampleSpacecraft* sample_spacecraft_; //!< Instance of spacecraft SampleGroundStation* sample_ground_station_; //!< Instance of ground station + + /** + * @fn Initialize + * @brief Override function of Initialize in SimulationCase + */ + void InitializeTargetObjects(); }; #endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index c7f9e72cc..980ea588a 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -32,6 +32,17 @@ SimulationCase::SimulationCase(const std::string initialize_base_file, const Mon SimulationCase::~SimulationCase() { delete global_environment_; } +void SimulationCase::Initialize() { + InitializeTargetObjects(); + + // Write headers to the log + simulation_configuration_.main_logger_->WriteHeaders(); + + // Start the simulation + std::cout << "\nSimulationDateTime \n"; + global_environment_->GetSimulationTime().PrintStartDateTime(); +} + std::string SimulationCase::GetLogHeader() const { std::string str_tmp = ""; @@ -64,4 +75,5 @@ void SimulationCase::InitializeSimulationConfiguration(const std::string initial // Global Environment global_environment_ = new GlobalEnvironment(&simulation_configuration_); + global_environment_->LogSetup(*(simulation_configuration_.main_logger_)); } \ No newline at end of file diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 8998ca24d..99a26a3a4 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -22,11 +22,15 @@ class SimulationCase : public ILoggable { /** * @fn SimulationCase * @brief Constructor + * @param[in] initialize_base_file: File path to initialize base file */ SimulationCase(const std::string initialize_base_file); /** * @fn SimulationCase * @brief Constructor for Monte-Carlo Simulation + * @param[in] initialize_base_file: File path to initialize base file + * @param[in] monte_carlo_simulator: Monte-Carlo simulator + * @param[in] log_path: Log output file path for Monte-Carlo simulation */ SimulationCase(const std::string initialize_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path); /** @@ -39,7 +43,7 @@ class SimulationCase : public ILoggable { * @fn Initialize * @brief Virtual function to initialize the simulation scenario */ - virtual void Initialize() = 0; + virtual void Initialize(); /** * @fn Main @@ -75,11 +79,18 @@ class SimulationCase : public ILoggable { GlobalEnvironment* global_environment_; //!< Global Environment /** - * @fn GetGlobalEnvironment - * @brief Return global environment + * @fn InitializeSimulationConfiguration + * @brief Initialize simulation configuration * @param[in] initialize_base_file: File path to initialize base file */ void InitializeSimulationConfiguration(const std::string initialize_base_file); + + /** + * @fn InitializeTargetObjects + * @brief Virtual function to initialize target objects(spacecraft and ground station) for the simulation + * @param[in] initialize_base_file: File path to initialize base file + */ + virtual void InitializeTargetObjects() = 0; }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From 253d09fb34e06290ef211270632aee302607cfab Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:38:46 +0100 Subject: [PATCH 1064/1086] Separate Main function to general part and user defined part to simplify the user codes --- src/simulation/case/sample_case.cpp | 38 +++++++------------------ src/simulation/case/sample_case.hpp | 18 ++++++------ src/simulation/case/simulation_case.cpp | 22 ++++++++++++++ src/simulation/case/simulation_case.hpp | 8 +++++- 4 files changed, 48 insertions(+), 38 deletions(-) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation/case/sample_case.cpp index b87e821a1..79bad3596 100644 --- a/src/simulation/case/sample_case.cpp +++ b/src/simulation/case/sample_case.cpp @@ -7,10 +7,7 @@ #include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" -using std::cout; -using std::string; - -SampleCase::SampleCase(string initialise_base_file) : SimulationCase(initialise_base_file) {} +SampleCase::SampleCase(std::string initialise_base_file) : SimulationCase(initialise_base_file) {} SampleCase::~SampleCase() { delete sample_spacecraft_; @@ -30,38 +27,23 @@ void SampleCase::InitializeTargetObjects() { sample_ground_station_->LogSetup(*(simulation_configuration_.main_logger_)); } -void SampleCase::Main() { - global_environment_->Reset(); // for MonteCarlo Simulation - while (!global_environment_->GetSimulationTime().GetState().finish) { - // Logging - if (global_environment_->GetSimulationTime().GetState().log_output) { - simulation_configuration_.main_logger_->WriteValues(); - } - - // Global Environment Update - global_environment_->Update(); - // Spacecraft Update - sample_spacecraft_->Update(&(global_environment_->GetSimulationTime())); - // Ground Station Update - sample_ground_station_->Update(global_environment_->GetCelestialInformation().GetEarthRotation(), *sample_spacecraft_); - - // Debug output - if (global_environment_->GetSimulationTime().GetState().disp_output) { - cout << "Progress: " << global_environment_->GetSimulationTime().GetProgressionRate() << "%\r"; - } - } +void SampleCase::UpdateTargetObjects() { + // Spacecraft Update + sample_spacecraft_->Update(&(global_environment_->GetSimulationTime())); + // Ground Station Update + sample_ground_station_->Update(global_environment_->GetCelestialInformation().GetEarthRotation(), *sample_spacecraft_); } -string SampleCase::GetLogHeader() const { - string str_tmp = ""; +std::string SampleCase::GetLogHeader() const { + std::string str_tmp = ""; str_tmp += WriteScalar("time", "s"); return str_tmp; } -string SampleCase::GetLogValue() const { - string str_tmp = ""; +std::string SampleCase::GetLogValue() const { + std::string str_tmp = ""; str_tmp += WriteScalar(global_environment_->GetSimulationTime().GetElapsedTime_s()); diff --git a/src/simulation/case/sample_case.hpp b/src/simulation/case/sample_case.hpp index 051883fb6..ae00c8355 100644 --- a/src/simulation/case/sample_case.hpp +++ b/src/simulation/case/sample_case.hpp @@ -20,7 +20,7 @@ class SampleCase : public SimulationCase { * @fn SampleCase * @brief Constructor */ - SampleCase(std::string initialise_base_file); + SampleCase(const std::string initialise_base_file); /** * @fn ~SampleCase @@ -28,12 +28,6 @@ class SampleCase : public SimulationCase { */ virtual ~SampleCase(); - /** - * @fn Main - * @brief Override function of Main in SimulationCase - */ - void Main(); - /** * @fn GetLogHeader * @brief Override function of GetLogHeader @@ -50,10 +44,16 @@ class SampleCase : public SimulationCase { SampleGroundStation* sample_ground_station_; //!< Instance of ground station /** - * @fn Initialize - * @brief Override function of Initialize in SimulationCase + * @fn InitializeTargetObjects + * @brief Override function of InitializeTargetObjects in SimulationCase */ void InitializeTargetObjects(); + + /** + * @fn UpdateTargetObjects + * @brief Override function of Main in SimulationCase + */ + void UpdateTargetObjects(); }; #endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 980ea588a..8450d3883 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -33,6 +33,7 @@ SimulationCase::SimulationCase(const std::string initialize_base_file, const Mon SimulationCase::~SimulationCase() { delete global_environment_; } void SimulationCase::Initialize() { + // Target Objects Initialize InitializeTargetObjects(); // Write headers to the log @@ -43,6 +44,27 @@ void SimulationCase::Initialize() { global_environment_->GetSimulationTime().PrintStartDateTime(); } +void SimulationCase::Main() { + global_environment_->Reset(); // for MonteCarlo Simulation + while (!global_environment_->GetSimulationTime().GetState().finish) { + // Logging + if (global_environment_->GetSimulationTime().GetState().log_output) { + simulation_configuration_.main_logger_->WriteValues(); + } + + // Global Environment Update + global_environment_->Update(); + + // Target Objects Update + UpdateTargetObjects(); + + // Debug output + if (global_environment_->GetSimulationTime().GetState().disp_output) { + std::cout << "Progress: " << global_environment_->GetSimulationTime().GetProgressionRate() << "%\r"; + } + } +} + std::string SimulationCase::GetLogHeader() const { std::string str_tmp = ""; diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index 99a26a3a4..b41db76bb 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -49,7 +49,7 @@ class SimulationCase : public ILoggable { * @fn Main * @brief Virtual function of main routine of the simulation scenario */ - virtual void Main() = 0; + virtual void Main(); /** * @fn GetLogHeader @@ -91,6 +91,12 @@ class SimulationCase : public ILoggable { * @param[in] initialize_base_file: File path to initialize base file */ virtual void InitializeTargetObjects() = 0; + + /** + * @fn UpdateTargetObjects + * @brief Virtual function to update target objects(spacecraft and ground station) + */ + virtual void UpdateTargetObjects() = 0; }; #endif // S2E_SIMULATION_CASE_SIMULATION_CASE_HPP_ From 1279674e1140e9031b72ee8acae14894d3f48e0c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:42:28 +0100 Subject: [PATCH 1065/1086] Fix initialize for log output --- src/simulation/ground_station/ground_station.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/simulation/ground_station/ground_station.hpp b/src/simulation/ground_station/ground_station.hpp index 7b98e0d85..2c6a06da6 100644 --- a/src/simulation/ground_station/ground_station.hpp +++ b/src/simulation/ground_station/ground_station.hpp @@ -94,8 +94,8 @@ class GroundStation : public ILoggable { protected: unsigned int ground_station_id_; //!< Ground station ID GeodeticPosition geodetic_position_; //!< Ground Station Position in the geodetic frame - Vector<3> position_ecef_m_; //!< Ground Station Position in the ECEF frame [m] - Vector<3> position_i_m_; //!< Ground Station Position in the inertial frame [m] + Vector<3> position_ecef_m_{0.0}; //!< Ground Station Position in the ECEF frame [m] + Vector<3> position_i_m_{0.0}; //!< Ground Station Position in the inertial frame [m] double elevation_limit_angle_deg_; //!< Minimum elevation angle to work the ground station [deg] std::map is_visible_; //!< Visible flag for each spacecraft ID (not care antenna) From e277c64304dea6bf7b545a19cdf85e35f859ffd5 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:48:09 +0100 Subject: [PATCH 1066/1086] Fix doxygen comments --- src/simulation/case/simulation_case.hpp | 1 - .../relative_information.hpp | 41 +++++++++---------- 2 files changed, 19 insertions(+), 23 deletions(-) diff --git a/src/simulation/case/simulation_case.hpp b/src/simulation/case/simulation_case.hpp index b41db76bb..b6aeba357 100644 --- a/src/simulation/case/simulation_case.hpp +++ b/src/simulation/case/simulation_case.hpp @@ -88,7 +88,6 @@ class SimulationCase : public ILoggable { /** * @fn InitializeTargetObjects * @brief Virtual function to initialize target objects(spacecraft and ground station) for the simulation - * @param[in] initialize_base_file: File path to initialize base file */ virtual void InitializeTargetObjects() = 0; diff --git a/src/simulation/multiple_spacecraft/relative_information.hpp b/src/simulation/multiple_spacecraft/relative_information.hpp index 5d950b679..afc6b1921 100644 --- a/src/simulation/multiple_spacecraft/relative_information.hpp +++ b/src/simulation/multiple_spacecraft/relative_information.hpp @@ -70,8 +70,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativeAttitudeQuaternion * @brief Return relative attitude quaternion of the target spacecraft with respect to the reference spacecraft - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline libra::Quaternion GetRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_attitude_quaternion_list_[target_spacecraft_id][reference_spacecraft_id]; @@ -79,8 +79,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativePosition_i_m * @brief Return relative position of the target spacecraft with respect to the reference spacecraft in the inertial frame and unit [m] - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline libra::Vector<3> GetRelativePosition_i_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_position_list_i_m_[target_spacecraft_id][reference_spacecraft_id]; @@ -88,8 +88,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativeVelocity_i_m * @brief Return relative velocity of the target spacecraft with respect to the reference spacecraft in the inertial frame and unit [m] - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline libra::Vector<3> GetRelativeVelocity_i_m_s(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_velocity_list_i_m_s_[target_spacecraft_id][reference_spacecraft_id]; @@ -97,8 +97,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativeDistance_m * @brief Return relative distance between the target spacecraft and the reference spacecraft in unit [m] - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline double GetRelativeDistance_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_distance_list_m_[target_spacecraft_id][reference_spacecraft_id]; @@ -106,9 +106,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativePosition_rtn_m * @brief Return relative position of the target spacecraft with respect to the reference spacecraft in the RTN frame of the reference spacecraft - * and unit [m] - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline libra::Vector<3> GetRelativePosition_rtn_m(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_position_list_rtn_m_[target_spacecraft_id][reference_spacecraft_id]; @@ -116,9 +115,8 @@ class RelativeInformation : public ILoggable { /** * @fn GetRelativeVelocity_rtn_m_s * @brief Return relative velocity of the target spacecraft with respect to the reference spacecraft in the RTN frame of the reference spacecraft - * and unit [m] - * @params [in] target_spacecraft_id: ID of target spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of target spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ inline libra::Vector<3> GetRelativeVelocity_rtn_m_s(const int target_spacecraft_id, const int reference_spacecraft_id) const { return relative_velocity_list_rtn_m_s_[target_spacecraft_id][reference_spacecraft_id]; @@ -127,8 +125,7 @@ class RelativeInformation : public ILoggable { /** * @fn GetReferenceSatDynamics * @brief Return the dynamics information of a spacecraft - * and unit [m] - * @params [in] target_spacecraft_id: ID of the spacecraft + * @param [in] target_spacecraft_id: ID of the spacecraft */ inline const Dynamics* GetReferenceSatDynamics(const int reference_spacecraft_id) const { return dynamics_database_.at(reference_spacecraft_id); }; @@ -145,22 +142,22 @@ class RelativeInformation : public ILoggable { /** * @fn CalcRelativeAttitudeQuaternion * @brief Calculate and return the relative attitude quaternion - * @params [in] target_spacecraft_id: ID of the spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of the spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ libra::Quaternion CalcRelativeAttitudeQuaternion(const int target_spacecraft_id, const int reference_spacecraft_id); /** * @fn CalcRelativePosition_rtn_m * @brief Calculate and return the relative position in RTN frame - * @params [in] target_spacecraft_id: ID of the spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of the spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ libra::Vector<3> CalcRelativePosition_rtn_m(const int target_spacecraft_id, const int reference_spacecraft_id); /** * @fn CalcRelativeVelocity_rtn_m_s * @brief Calculate and return the relative velocity in RTN frame - * @params [in] target_spacecraft_id: ID of the spacecraft - * @params [in] reference_spacecraft_id: ID of reference spacecraft + * @param [in] target_spacecraft_id: ID of the spacecraft + * @param [in] reference_spacecraft_id: ID of reference spacecraft */ libra::Vector<3> CalcRelativeVelocity_rtn_m_s(const int target_spacecraft_id, const int reference_spacecraft_id); From 8a3186743a1ed3d911ed8c34178b18fba449d87a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 21 Mar 2023 15:54:02 +0100 Subject: [PATCH 1067/1086] Integrate constructors using default value settings for arguments --- src/simulation/spacecraft/spacecraft.cpp | 31 ++++++------------------ src/simulation/spacecraft/spacecraft.hpp | 17 +++---------- 2 files changed, 10 insertions(+), 38 deletions(-) diff --git a/src/simulation/spacecraft/spacecraft.cpp b/src/simulation/spacecraft/spacecraft.cpp index dce592086..17c204c64 100644 --- a/src/simulation/spacecraft/spacecraft.cpp +++ b/src/simulation/spacecraft/spacecraft.cpp @@ -8,15 +8,10 @@ #include #include -Spacecraft::Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id) +Spacecraft::Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id, + RelativeInformation* relative_information) : spacecraft_id_(spacecraft_id) { - Initialize(simulation_configuration, global_environment, spacecraft_id); -} - -Spacecraft::Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - RelativeInformation* relative_information, const int spacecraft_id) - : spacecraft_id_(spacecraft_id) { - Initialize(simulation_configuration, global_environment, relative_information, spacecraft_id); + Initialize(simulation_configuration, global_environment, spacecraft_id, relative_information); } Spacecraft::~Spacecraft() { @@ -31,21 +26,7 @@ Spacecraft::~Spacecraft() { } void Spacecraft::Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - const int spacecraft_id) { - clock_generator_.ClearTimerCount(); - structure_ = new Structure(simulation_configuration, spacecraft_id); - local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); - dynamics_ = new Dynamics(simulation_configuration, &(global_environment->GetSimulationTime()), &(local_environment_->GetCelestialInformation()), - spacecraft_id, structure_); - disturbances_ = new Disturbances(simulation_configuration, spacecraft_id, structure_, global_environment); - - simulation_configuration->main_logger_->CopyFileToLogDirectory(simulation_configuration->spacecraft_file_list_[spacecraft_id]); - - relative_information_ = nullptr; -} - -void Spacecraft::Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - RelativeInformation* relative_information, const int spacecraft_id) { + const int spacecraft_id, RelativeInformation* relative_information) { clock_generator_.ClearTimerCount(); structure_ = new Structure(simulation_configuration, spacecraft_id); local_environment_ = new LocalEnvironment(simulation_configuration, global_environment, spacecraft_id); @@ -56,7 +37,9 @@ void Spacecraft::Initialize(const SimulationConfiguration* simulation_configurat simulation_configuration->main_logger_->CopyFileToLogDirectory(simulation_configuration->spacecraft_file_list_[spacecraft_id]); relative_information_ = relative_information; - relative_information_->RegisterDynamicsInfo(spacecraft_id, dynamics_); + if (relative_information_ != nullptr) { + relative_information_->RegisterDynamicsInfo(spacecraft_id, dynamics_); + } } void Spacecraft::LogSetup(Logger& logger) { diff --git a/src/simulation/spacecraft/spacecraft.hpp b/src/simulation/spacecraft/spacecraft.hpp index 5baf27f33..2d9552f24 100644 --- a/src/simulation/spacecraft/spacecraft.hpp +++ b/src/simulation/spacecraft/spacecraft.hpp @@ -25,13 +25,8 @@ class Spacecraft { * @fn Spacecraft * @brief Constructor for single satellite simulation */ - Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id); - /** - * @fn Spacecraft - * @brief Constructor for multiple satellite simulation - */ - Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - RelativeInformation* relative_information, const int spacecraft_id); + Spacecraft(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, const int spacecraft_id, + RelativeInformation* relative_information = nullptr); /** * @fn ~Spacecraft @@ -44,18 +39,12 @@ class Spacecraft { Spacecraft& operator=(const Spacecraft&) = delete; // Virtual functions - /** - * @fn Initialize - * @brief Initialize function for single spacecraft simulation - */ - virtual void Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - const int spacecraft_id); /** * @fn Initialize * @brief Initialize function for multiple spacecraft simulation */ virtual void Initialize(const SimulationConfiguration* simulation_configuration, const GlobalEnvironment* global_environment, - RelativeInformation* relative_information, const int spacecraft_id); + const int spacecraft_id, RelativeInformation* relative_information = nullptr); /** * @fn Update From c774155b8d5d53fb3a7c9d21501c55ed9b5ad98e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Wed, 22 Mar 2023 14:15:12 +0100 Subject: [PATCH 1068/1086] Fix to use tolower function with locale --- src/environment/global/celestial_information.cpp | 5 ++++- src/environment/local/local_celestial_information.cpp | 5 ++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 73b0a9c56..45bf3c25c 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -156,7 +156,10 @@ std::string CelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, kMaxNameLength, name_buffer, (SpiceBoolean*)&found); std::string name = name_buffer; - std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return (char)std::tolower(c); }); + + std::locale loc = std::locale::classic(); + std::transform(name.begin(), name.end(), name.begin(), [loc](char c) { return std::tolower(c, loc); }); + std::string body_pos = name + "_position"; std::string body_vel = name + "_velocity"; diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index 4f31300b2..b8fb58b34 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -172,7 +172,10 @@ std::string LocalCelestialInformation::GetLogHeader() const { // Acquisition of body name from id bodc2n_c(planet_id, maxlen, namebuf, (SpiceBoolean*)&found); std::string name = namebuf; - std::transform(name.begin(), name.end(), name.begin(), [](unsigned char c) { return (char)std::tolower(c); }); + + std::locale loc = std::locale::classic(); + std::transform(name.begin(), name.end(), name.begin(), [loc](char c) { return std::tolower(c, loc); }); + std::string body_pos = name + "_position_from_spacecraft"; std::string body_vel = name + "_velocity_from_spacecraft"; str_tmp += WriteVector(body_pos, "b", "m", 3); From c4f7acf3483af41fac98e3c9c5c352a7b4211d73 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Mar 2023 10:14:52 +0100 Subject: [PATCH 1069/1086] Add include for Visual Studio --- src/environment/global/celestial_information.cpp | 1 + src/environment/local/local_celestial_information.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/src/environment/global/celestial_information.cpp b/src/environment/global/celestial_information.cpp index 45bf3c25c..eb1feba9f 100644 --- a/src/environment/global/celestial_information.cpp +++ b/src/environment/global/celestial_information.cpp @@ -11,6 +11,7 @@ #include #include +#include #include #include "library/logger/log_utility.hpp" diff --git a/src/environment/local/local_celestial_information.cpp b/src/environment/local/local_celestial_information.cpp index b8fb58b34..dc4737853 100644 --- a/src/environment/local/local_celestial_information.cpp +++ b/src/environment/local/local_celestial_information.cpp @@ -9,6 +9,7 @@ #include #include +#include #include #include "library/logger/log_utility.hpp" From 21497f9dfca083451ed93a6e0d92ce87aae1b15c Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Mar 2023 15:52:29 +0100 Subject: [PATCH 1070/1086] Make simulation_sample directory and move files --- src/{simulation => simulation_sample}/case/sample_case.cpp | 0 src/{simulation => simulation_sample}/case/sample_case.hpp | 0 .../ground_station}/sample_ground_station.cpp | 0 .../ground_station}/sample_ground_station.hpp | 0 .../ground_station}/sample_ground_station_components.cpp | 0 .../ground_station}/sample_ground_station_components.hpp | 0 .../spacecraft}/sample_components.cpp | 0 .../spacecraft}/sample_components.hpp | 0 .../spacecraft}/sample_port_configuration.hpp | 0 .../spacecraft}/sample_spacecraft.cpp | 0 .../spacecraft}/sample_spacecraft.hpp | 0 11 files changed, 0 insertions(+), 0 deletions(-) rename src/{simulation => simulation_sample}/case/sample_case.cpp (100%) rename src/{simulation => simulation_sample}/case/sample_case.hpp (100%) rename src/{simulation/ground_station/sample_ground_station => simulation_sample/ground_station}/sample_ground_station.cpp (100%) rename src/{simulation/ground_station/sample_ground_station => simulation_sample/ground_station}/sample_ground_station.hpp (100%) rename src/{simulation/ground_station/sample_ground_station => simulation_sample/ground_station}/sample_ground_station_components.cpp (100%) rename src/{simulation/ground_station/sample_ground_station => simulation_sample/ground_station}/sample_ground_station_components.hpp (100%) rename src/{simulation/spacecraft/sample_spacecraft => simulation_sample/spacecraft}/sample_components.cpp (100%) rename src/{simulation/spacecraft/sample_spacecraft => simulation_sample/spacecraft}/sample_components.hpp (100%) rename src/{simulation/spacecraft/sample_spacecraft => simulation_sample/spacecraft}/sample_port_configuration.hpp (100%) rename src/{simulation/spacecraft/sample_spacecraft => simulation_sample/spacecraft}/sample_spacecraft.cpp (100%) rename src/{simulation/spacecraft/sample_spacecraft => simulation_sample/spacecraft}/sample_spacecraft.hpp (100%) diff --git a/src/simulation/case/sample_case.cpp b/src/simulation_sample/case/sample_case.cpp similarity index 100% rename from src/simulation/case/sample_case.cpp rename to src/simulation_sample/case/sample_case.cpp diff --git a/src/simulation/case/sample_case.hpp b/src/simulation_sample/case/sample_case.hpp similarity index 100% rename from src/simulation/case/sample_case.hpp rename to src/simulation_sample/case/sample_case.hpp diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp b/src/simulation_sample/ground_station/sample_ground_station.cpp similarity index 100% rename from src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp rename to src/simulation_sample/ground_station/sample_ground_station.cpp diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp b/src/simulation_sample/ground_station/sample_ground_station.hpp similarity index 100% rename from src/simulation/ground_station/sample_ground_station/sample_ground_station.hpp rename to src/simulation_sample/ground_station/sample_ground_station.hpp diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp b/src/simulation_sample/ground_station/sample_ground_station_components.cpp similarity index 100% rename from src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp rename to src/simulation_sample/ground_station/sample_ground_station_components.cpp diff --git a/src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp b/src/simulation_sample/ground_station/sample_ground_station_components.hpp similarity index 100% rename from src/simulation/ground_station/sample_ground_station/sample_ground_station_components.hpp rename to src/simulation_sample/ground_station/sample_ground_station_components.hpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.cpp b/src/simulation_sample/spacecraft/sample_components.cpp similarity index 100% rename from src/simulation/spacecraft/sample_spacecraft/sample_components.cpp rename to src/simulation_sample/spacecraft/sample_components.cpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_components.hpp b/src/simulation_sample/spacecraft/sample_components.hpp similarity index 100% rename from src/simulation/spacecraft/sample_spacecraft/sample_components.hpp rename to src/simulation_sample/spacecraft/sample_components.hpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp b/src/simulation_sample/spacecraft/sample_port_configuration.hpp similarity index 100% rename from src/simulation/spacecraft/sample_spacecraft/sample_port_configuration.hpp rename to src/simulation_sample/spacecraft/sample_port_configuration.hpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp b/src/simulation_sample/spacecraft/sample_spacecraft.cpp similarity index 100% rename from src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp rename to src/simulation_sample/spacecraft/sample_spacecraft.cpp diff --git a/src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp b/src/simulation_sample/spacecraft/sample_spacecraft.hpp similarity index 100% rename from src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.hpp rename to src/simulation_sample/spacecraft/sample_spacecraft.hpp From d14b9e0599a417acdecaa362caf6707781473969 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 23 Mar 2023 16:03:57 +0100 Subject: [PATCH 1071/1086] Fix file path --- CMakeLists.txt | 10 +++++----- src/s2e.cpp | 2 +- src/simulation_sample/case/sample_case.cpp | 2 -- src/simulation_sample/case/sample_case.hpp | 13 +++++++------ .../ground_station/sample_ground_station.hpp | 10 +++++----- .../sample_ground_station_components.hpp | 6 +++--- .../spacecraft/sample_components.hpp | 7 +++---- .../spacecraft/sample_port_configuration.hpp | 6 +++--- .../spacecraft/sample_spacecraft.hpp | 9 +++++---- 9 files changed, 32 insertions(+), 33 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e6075c11d..dd99ab26b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,11 +73,11 @@ add_subdirectory(src/library) set(SOURCE_FILES src/s2e.cpp - src/simulation/case/sample_case.cpp - src/simulation/spacecraft/sample_spacecraft/sample_spacecraft.cpp - src/simulation/spacecraft/sample_spacecraft/sample_components.cpp - src/simulation/ground_station/sample_ground_station/sample_ground_station_components.cpp - src/simulation/ground_station/sample_ground_station/sample_ground_station.cpp + src/simulation_sample/case/sample_case.cpp + src/simulation_sample/spacecraft/sample_spacecraft.cpp + src/simulation_sample/spacecraft/sample_components.cpp + src/simulation_sample/ground_station/sample_ground_station_components.cpp + src/simulation_sample/ground_station/sample_ground_station.cpp ) ## Create executable file diff --git a/src/s2e.cpp b/src/s2e.cpp index c3eca722d..63001e86f 100644 --- a/src/s2e.cpp +++ b/src/s2e.cpp @@ -18,7 +18,7 @@ #include "library/logger/logger.hpp" // Add custom include files -#include "simulation/case/sample_case.hpp" +#include "simulation_sample/case/sample_case.hpp" // #include "simulation/monte_carlo_simulation/monte_carlo_simulation_executor.hpp" // #include "interface/hils/COSMOSWrapper.h" // #include "interface/hils/HardwareMessage.h" diff --git a/src/simulation_sample/case/sample_case.cpp b/src/simulation_sample/case/sample_case.cpp index 79bad3596..ce6376ebe 100644 --- a/src/simulation_sample/case/sample_case.cpp +++ b/src/simulation_sample/case/sample_case.cpp @@ -5,8 +5,6 @@ #include "sample_case.hpp" -#include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" - SampleCase::SampleCase(std::string initialise_base_file) : SimulationCase(initialise_base_file) {} SampleCase::~SampleCase() { diff --git a/src/simulation_sample/case/sample_case.hpp b/src/simulation_sample/case/sample_case.hpp index ae00c8355..a4664a190 100644 --- a/src/simulation_sample/case/sample_case.hpp +++ b/src/simulation_sample/case/sample_case.hpp @@ -3,12 +3,13 @@ * @brief Example of user defined simulation case */ -#ifndef S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ -#define S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_CASE_SAMPLE_CASE_HPP_ +#define S2E_SIMULATION_SAMPLE_CASE_SAMPLE_CASE_HPP_ -#include "../ground_station/sample_ground_station/sample_ground_station.hpp" -#include "../spacecraft/sample_spacecraft/sample_spacecraft.hpp" -#include "./simulation_case.hpp" +#include + +#include "../ground_station/sample_ground_station.hpp" +#include "../spacecraft/sample_spacecraft.hpp" /** * @class SampleCase @@ -56,4 +57,4 @@ class SampleCase : public SimulationCase { void UpdateTargetObjects(); }; -#endif // S2E_SIMULATION_CASE_SAMPLE_CASE_HPP_ +#endif // S2E_SIMULATION_SAMPLE_CASE_SAMPLE_CASE_HPP_ diff --git a/src/simulation_sample/ground_station/sample_ground_station.hpp b/src/simulation_sample/ground_station/sample_ground_station.hpp index 8b4006b4e..64990e75a 100644 --- a/src/simulation_sample/ground_station/sample_ground_station.hpp +++ b/src/simulation_sample/ground_station/sample_ground_station.hpp @@ -3,16 +3,16 @@ * @brief An example of user defined ground station class */ -#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ -#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ +#define S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ #include #include #include #include +#include -#include "../../spacecraft/sample_spacecraft/sample_spacecraft.hpp" -#include "../ground_station.hpp" +#include "../spacecraft/sample_spacecraft.hpp" class SampleGsComponents; @@ -53,4 +53,4 @@ class SampleGroundStation : public GroundStation { SampleGsComponents* components_; //!< Ground station related components }; -#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ +#endif // S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_HPP_ diff --git a/src/simulation_sample/ground_station/sample_ground_station_components.hpp b/src/simulation_sample/ground_station/sample_ground_station_components.hpp index 1d3549880..067ddd2d8 100644 --- a/src/simulation_sample/ground_station/sample_ground_station_components.hpp +++ b/src/simulation_sample/ground_station/sample_ground_station_components.hpp @@ -3,8 +3,8 @@ * @brief An example of ground station related components list */ -#ifndef S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ -#define S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ +#define S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ #include #include @@ -49,4 +49,4 @@ class SampleGsComponents { const SimulationConfiguration* configuration_; //!< Simulation setting }; -#endif // S2E_SIMULATION_GROUND_STATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ +#endif // S2E_SIMULATION_SAMPLE_GROUND_STATION_SAMPLE_GROUND_STATION_COMPONENTS_HPP_ diff --git a/src/simulation_sample/spacecraft/sample_components.hpp b/src/simulation_sample/spacecraft/sample_components.hpp index 1b8a5f383..854158409 100644 --- a/src/simulation_sample/spacecraft/sample_components.hpp +++ b/src/simulation_sample/spacecraft/sample_components.hpp @@ -3,8 +3,8 @@ * @brief An example of user side components management installed on a spacecraft */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ +#define S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ #include #include @@ -26,10 +26,9 @@ #include #include #include +#include #include -#include "../installed_components.hpp" - class OnBoardComputer; class PowerControlUnit; class GyroSensor; diff --git a/src/simulation_sample/spacecraft/sample_port_configuration.hpp b/src/simulation_sample/spacecraft/sample_port_configuration.hpp index 24ff21316..413e22fce 100644 --- a/src/simulation_sample/spacecraft/sample_port_configuration.hpp +++ b/src/simulation_sample/spacecraft/sample_port_configuration.hpp @@ -3,8 +3,8 @@ * @brief An example of port configuration management */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ +#define S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ /** * @enum PowerPortConfig @@ -27,4 +27,4 @@ enum class UARTPortConfig { kUartComponentMax //!< Maximum port number. Do not remove. Place on the bottom. }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ +#endif // S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_PORT_CONFIGURATION_HPP_ diff --git a/src/simulation_sample/spacecraft/sample_spacecraft.hpp b/src/simulation_sample/spacecraft/sample_spacecraft.hpp index a3d21e020..26df81ba6 100644 --- a/src/simulation_sample/spacecraft/sample_spacecraft.hpp +++ b/src/simulation_sample/spacecraft/sample_spacecraft.hpp @@ -3,10 +3,11 @@ * @brief An example of user side spacecraft class */ -#ifndef S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ -#define S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ +#ifndef S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ +#define S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ + +#include -#include "../spacecraft.hpp" #include "sample_components.hpp" class SampleComponents; @@ -34,4 +35,4 @@ class SampleSpacecraft : public Spacecraft { SampleComponents* sample_components_; }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ +#endif // SS2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ From 73b0f85bbe6bb4c8411a787fa390e21406d6872e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Mar 2023 05:38:17 +0100 Subject: [PATCH 1072/1086] Fix include guard comment --- src/simulation_sample/spacecraft/sample_components.hpp | 2 +- src/simulation_sample/spacecraft/sample_spacecraft.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/simulation_sample/spacecraft/sample_components.hpp b/src/simulation_sample/spacecraft/sample_components.hpp index 854158409..7b2b57449 100644 --- a/src/simulation_sample/spacecraft/sample_components.hpp +++ b/src/simulation_sample/spacecraft/sample_components.hpp @@ -118,4 +118,4 @@ class SampleComponents : public InstalledComponents { const GlobalEnvironment* global_environment_; //!< Global environment information }; -#endif // S2E_SIMULATION_SPACECRAFT_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ +#endif // S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_COMPONENTS_HPP_ diff --git a/src/simulation_sample/spacecraft/sample_spacecraft.hpp b/src/simulation_sample/spacecraft/sample_spacecraft.hpp index 26df81ba6..1436dbfe1 100644 --- a/src/simulation_sample/spacecraft/sample_spacecraft.hpp +++ b/src/simulation_sample/spacecraft/sample_spacecraft.hpp @@ -35,4 +35,4 @@ class SampleSpacecraft : public Spacecraft { SampleComponents* sample_components_; }; -#endif // SS2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ +#endif // S2E_SIMULATION_SAMPLE_SPACECRAFT_SAMPLE_SPACECRAFT_HPP_ From 017c2af459f869d75bae5c968a7a9d252c37cd7a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Fri, 24 Mar 2023 14:30:35 +0100 Subject: [PATCH 1073/1086] Fix include path in telescope.h --- src/components/real/mission/telescope.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/components/real/mission/telescope.hpp b/src/components/real/mission/telescope.hpp index 7dd89ea81..ec8218234 100644 --- a/src/components/real/mission/telescope.hpp +++ b/src/components/real/mission/telescope.hpp @@ -6,7 +6,6 @@ #ifndef S2E_COMPONENTS_REAL_MISSION_TELESCOPE_HPP_P_ #define S2E_COMPONENTS_REAL_MISSION_TELESCOPE_HPP_P_ -#include #include #include #include @@ -15,6 +14,8 @@ #include #include +#include "../../base/component.hpp" + /* * @struct Star * @brief Information of stars in the telescope's field of view From b585050ed5945d69529e11d027adf6222b194cdf Mon Sep 17 00:00:00 2001 From: kai0722 Date: Thu, 30 Mar 2023 15:13:11 +0900 Subject: [PATCH 1074/1086] add initialize sequence with initialize_mode --- .../initialize_files/sample_satellite.ini | 5 ++++ src/dynamics/attitude/initialize_attitude.cpp | 28 ++++++++++++++++++- src/library/math/s2e_math 2.cpp | 26 +++++++++++++++++ src/library/math/s2e_math 2.hpp | 18 ++++++++++++ 4 files changed, 76 insertions(+), 1 deletion(-) create mode 100644 src/library/math/s2e_math 2.cpp create mode 100644 src/library/math/s2e_math 2.hpp diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index af6657a46..173f86c8f 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -4,6 +4,11 @@ // CONTROLLED : Attitude Calculation with Controlled Attitude mode. All disturbances and control torque are ignored. propagate_mode = RK4 +// Initialize Attitude mode +// MANUAL : Initialize Quaternion_i2b manually below +// CONTROLLED : Initialize attitude with given condition. Valid only when Attitude propagation mode is RK4. +initialize_mode = MANUAL + // Initial angular velocity at body frame [rad/s] initial_angular_velocity_b_rad_s(0) = 0.0 initial_angular_velocity_b_rad_s(1) = 0.0 diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 0383b8c62..3f7847b82 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -12,10 +12,12 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel const char* section_ = "ATTITUDE"; std::string mc_name = section_ + std::to_string(spacecraft_id); // FIXME Attitude* attitude; + Attitude* attitude_tmp; const std::string propagate_mode = ini_file.ReadString(section_, "propagate_mode"); + const std::string initialize_mode = ini_file.ReadString(section_, "initialize_mode"); - if (propagate_mode == "RK4") { + if (propagate_mode == "RK4" && initialize_mode == "MANUAL") { // RK4 propagator libra::Vector<3> omega_b; ini_file.ReadVector(section_, "initial_angular_velocity_b_rad_s", omega_b); @@ -24,6 +26,29 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel libra::Vector<3> torque_b; ini_file.ReadVector(section_, "initial_torque_b_Nm", torque_b); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); + } else if (propagate_mode == "RK4" && initialize_mode == "CONTROLLED") { + // Initialize with Controlled attitude (attitude_tmp temporary used) + IniAccess ini_file_ca(file_name); + const char* section_ca_ = "CONTROLLED_ATTITUDE"; + const std::string main_mode_in = ini_file.ReadString(section_ca_, "main_mode"); + const std::string sub_mode_in = ini_file.ReadString(section_ca_, "sub_mode"); + + AttitudeControlMode main_mode = ConvertStringToCtrlMode(main_mode_in); + AttitudeControlMode sub_mode = ConvertStringToCtrlMode(sub_mode_in); + libra::Quaternion quaternion_i2b; + ini_file_ca.ReadQuaternion(section_, "initial_quaternion_i2b", quaternion_i2b); + libra::Vector<3> main_target_direction_b, sub_target_direction_b; + ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); + ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); + + attitude_tmp = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor_kgm2, + local_celestial_information, orbit, mc_name); + attitude_tmp->Propagate(step_width_s); + quaternion_i2b = attitude_tmp->GetQuaternion_i2b(); + libra::Vector<3> omega_b = libra::Vector<3>(0); + libra::Vector<3> torque_b = libra::Vector<3>(0); + attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); } else if (propagate_mode == "CONTROLLED") { // Controlled attitude @@ -39,6 +64,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel libra::Vector<3> main_target_direction_b, sub_target_direction_b; ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); + attitude = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor_kgm2, local_celestial_information, orbit, mc_name); } else { diff --git a/src/library/math/s2e_math 2.cpp b/src/library/math/s2e_math 2.cpp new file mode 100644 index 000000000..5cf6e1a0a --- /dev/null +++ b/src/library/math/s2e_math 2.cpp @@ -0,0 +1,26 @@ +/** + * @file s2e_math.cpp + * @brief Math functions + */ + +#include "s2e_math.hpp" + +#include + +namespace libra { +double WrapTo2Pi(const double angle) { + double angle_out = angle; + if (angle_out < 0.0) { + while (angle_out < 0.0) { + angle_out += libra::tau; + } + } else if (angle_out > libra::tau) { + while (angle_out > libra::tau) { + angle_out -= libra::tau; + } + } else { + // nothing to do + } + return angle_out; +} +} // namespace libra diff --git a/src/library/math/s2e_math 2.hpp b/src/library/math/s2e_math 2.hpp new file mode 100644 index 000000000..26a63b1cf --- /dev/null +++ b/src/library/math/s2e_math 2.hpp @@ -0,0 +1,18 @@ +/** + * @file s2e_math.hpp + * @brief Math functions + */ + +#pragma once +#include + +namespace libra { + +/** + * @fn WrapTo2Pi + * @brief Wrap angle value into [0, 2pi] + * @param angle: Angle [rad] + */ +double WrapTo2Pi(const double angle); + +} // namespace libra From ce453b468a248e57ead02bf93b5a1424dc57046a Mon Sep 17 00:00:00 2001 From: kai0722 <69716740+kai0722@users.noreply.github.com> Date: Sun, 2 Apr 2023 22:26:51 +0900 Subject: [PATCH 1075/1086] Delete s2e_math 2.cpp --- src/library/math/s2e_math 2.cpp | 26 -------------------------- 1 file changed, 26 deletions(-) delete mode 100644 src/library/math/s2e_math 2.cpp diff --git a/src/library/math/s2e_math 2.cpp b/src/library/math/s2e_math 2.cpp deleted file mode 100644 index 5cf6e1a0a..000000000 --- a/src/library/math/s2e_math 2.cpp +++ /dev/null @@ -1,26 +0,0 @@ -/** - * @file s2e_math.cpp - * @brief Math functions - */ - -#include "s2e_math.hpp" - -#include - -namespace libra { -double WrapTo2Pi(const double angle) { - double angle_out = angle; - if (angle_out < 0.0) { - while (angle_out < 0.0) { - angle_out += libra::tau; - } - } else if (angle_out > libra::tau) { - while (angle_out > libra::tau) { - angle_out -= libra::tau; - } - } else { - // nothing to do - } - return angle_out; -} -} // namespace libra From ed3fb812618056fd9f8cc3275f8e76ad961c96b5 Mon Sep 17 00:00:00 2001 From: kai0722 <69716740+kai0722@users.noreply.github.com> Date: Sun, 2 Apr 2023 22:27:06 +0900 Subject: [PATCH 1076/1086] Delete s2e_math 2.hpp --- src/library/math/s2e_math 2.hpp | 18 ------------------ 1 file changed, 18 deletions(-) delete mode 100644 src/library/math/s2e_math 2.hpp diff --git a/src/library/math/s2e_math 2.hpp b/src/library/math/s2e_math 2.hpp deleted file mode 100644 index 26a63b1cf..000000000 --- a/src/library/math/s2e_math 2.hpp +++ /dev/null @@ -1,18 +0,0 @@ -/** - * @file s2e_math.hpp - * @brief Math functions - */ - -#pragma once -#include - -namespace libra { - -/** - * @fn WrapTo2Pi - * @brief Wrap angle value into [0, 2pi] - * @param angle: Angle [rad] - */ -double WrapTo2Pi(const double angle); - -} // namespace libra From 40dd85f8fee02d166a4b2bf185ab871869ffaefc Mon Sep 17 00:00:00 2001 From: kai0722 <69716740+kai0722@users.noreply.github.com> Date: Sun, 2 Apr 2023 22:37:10 +0900 Subject: [PATCH 1077/1086] Update initialize_attitude.cpp --- src/dynamics/attitude/initialize_attitude.cpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 3f7847b82..c322013c0 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -12,7 +12,6 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel const char* section_ = "ATTITUDE"; std::string mc_name = section_ + std::to_string(spacecraft_id); // FIXME Attitude* attitude; - Attitude* attitude_tmp; const std::string propagate_mode = ini_file.ReadString(section_, "propagate_mode"); const std::string initialize_mode = ini_file.ReadString(section_, "initialize_mode"); @@ -41,13 +40,13 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel libra::Vector<3> main_target_direction_b, sub_target_direction_b; ini_file_ca.ReadVector(section_ca_, "main_pointing_direction_b", main_target_direction_b); ini_file_ca.ReadVector(section_ca_, "sub_pointing_direction_b", sub_target_direction_b); - - attitude_tmp = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, inertia_tensor_kgm2, - local_celestial_information, orbit, mc_name); - attitude_tmp->Propagate(step_width_s); - quaternion_i2b = attitude_tmp->GetQuaternion_i2b(); - libra::Vector<3> omega_b = libra::Vector<3>(0); - libra::Vector<3> torque_b = libra::Vector<3>(0); + std::string mc_name_temp = section_ + std::to_string(spacecraft_id) + "_TEMP"; + Attitude* attitude_temp = new ControlledAttitude(main_mode, sub_mode, quaternion_i2b, main_target_direction_b, sub_target_direction_b, + inertia_tensor_kgm2, local_celestial_information, orbit, mc_name_temp); + attitude_temp->Propagate(step_width_s); + quaternion_i2b = attitude_temp->GetQuaternion_i2b(); + libra::Vector<3> omega_b = libra::Vector<3>(0.0); + libra::Vector<3> torque_b = libra::Vector<3>(0.0); attitude = new AttitudeRk4(omega_b, quaternion_i2b, inertia_tensor_kgm2, torque_b, step_width_s, mc_name); } else if (propagate_mode == "CONTROLLED") { From e0b4e4ca32ef3c72ad2a9bc00804d76ed12590c8 Mon Sep 17 00:00:00 2001 From: kai0722 <69716740+kai0722@users.noreply.github.com> Date: Sun, 2 Apr 2023 22:41:49 +0900 Subject: [PATCH 1078/1086] Update controlled_attitude.cpp --- src/dynamics/attitude/controlled_attitude.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/dynamics/attitude/controlled_attitude.cpp b/src/dynamics/attitude/controlled_attitude.cpp index 2f07b614f..db336ba00 100644 --- a/src/dynamics/attitude/controlled_attitude.cpp +++ b/src/dynamics/attitude/controlled_attitude.cpp @@ -79,8 +79,20 @@ libra::Vector<3> ControlledAttitude::CalcTargetDirection_i(AttitudeControlMode m libra::Vector<3> direction; if (mode == AttitudeControlMode::kSunPointing) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("SUN"); + // When the local_celestial_information is not initialized. FIXME: This is temporary codes for attitude initialize. + if (direction.CalcNorm() == 0.0) { + libra::Vector<3> sun_position_i_m = local_celestial_information_->GetGlobalInformation().GetPositionFromCenter_i_m("SUN"); + libra::Vector<3> spacecraft_position_i_m = orbit_->GetPosition_i_m(); + direction = sun_position_i_m - spacecraft_position_i_m; + } } else if (mode == AttitudeControlMode::kEarthCenterPointing) { direction = local_celestial_information_->GetPositionFromSpacecraft_i_m("EARTH"); + // When the local_celestial_information is not initialized. FIXME: This is temporary codes for attitude initialize. + if (direction.CalcNorm() == 0.0) { + libra::Vector<3> earth_position_i_m = local_celestial_information_->GetGlobalInformation().GetPositionFromCenter_i_m("EARTH"); + libra::Vector<3> spacecraft_position_i_m = orbit_->GetPosition_i_m(); + direction = earth_position_i_m - spacecraft_position_i_m; + } } else if (mode == AttitudeControlMode::kVelocityDirectionPointing) { direction = orbit_->GetVelocity_i_m_s(); } else if (mode == AttitudeControlMode::kOrbitNormalPointing) { From f88fe5e24272ea2eeb213722225232372a51ccff Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Mon, 3 Apr 2023 12:51:47 +0200 Subject: [PATCH 1079/1086] Fix comments in ini files --- data/sample/initialize_files/sample_simulation_base.ini | 5 +++-- data/sample/initialize_files/sample_structure.ini | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 62dc896bb..49df9495f 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -129,8 +129,9 @@ rand_seed = 0x11223344 save_initialize_files = ENABLE // Initialize files -// File name must not over 256 characters (defined in initialize.h as MAX_CHAR_NUM) -// If you want to add a spacecraft, create the corresponding Sat.ini, and specify it as sat_file(1), sat_file(2)... . +// File name must not over 1024 characters (defined in initialize_file_access.hpp as kMaxCharLength) +// If you want to add a spacecraft, create the corresponding spacecraft.ini, and specify it as spacecraft_file(1), spacecraft_file(2), ect. +// If you want to add a ground station, create the corresponding ground_station.ini, and specify it as ground_station_file(1), ground_station_file(2), ect. number_of_simulated_spacecraft = 1 number_of_simulated_ground_station = 1 spacecraft_file(0) = ../../data/sample/initialize_files/sample_satellite.ini diff --git a/data/sample/initialize_files/sample_structure.ini b/data/sample/initialize_files/sample_structure.ini index 898997f29..b7c707cb5 100644 --- a/data/sample/initialize_files/sample_structure.ini +++ b/data/sample/initialize_files/sample_structure.ini @@ -1,7 +1,7 @@ // // The origin of all vectors defined here is the body-fixed frame. // Users can define the origin of the body-fixed frame by themselves. -// If users want to define the origin as the center of gravity, they need to set cg_b = zero vector. +// If users want to define the origin as the center of gravity, they need to set center_of_gravity_b_m = zero vector. // If users want to define the origin as a specific point, they need to set all vectors to suit their definition carefully. // From c9e080dd4a2cb672945d27916cf76c295da2e90f Mon Sep 17 00:00:00 2001 From: kai0722 Date: Mon, 3 Apr 2023 20:07:41 +0900 Subject: [PATCH 1080/1086] add logs_230403_195908 --- .../initialize_files/sample_satellite.ini | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index 173f86c8f..9853c857c 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -7,7 +7,7 @@ propagate_mode = RK4 // Initialize Attitude mode // MANUAL : Initialize Quaternion_i2b manually below // CONTROLLED : Initialize attitude with given condition. Valid only when Attitude propagation mode is RK4. -initialize_mode = MANUAL +initialize_mode = CONTROLLED // Initial angular velocity at body frame [rad/s] initial_angular_velocity_b_rad_s(0) = 0.0 @@ -16,10 +16,10 @@ initial_angular_velocity_b_rad_s(2) = 0.0 // Initial quaternion inertial frame to body frame (real part, imaginary part) // This value also used in INERTIAL_STABILIZE mode of ControlledAttitude -initial_quaternion_i2b(0) = 0.0 -initial_quaternion_i2b(1) = 0.0 -initial_quaternion_i2b(2) = 0.0 -initial_quaternion_i2b(3) = 1.0 +initial_quaternion_i2b(0) = 1.0 +initial_quaternion_i2b(1) = 2.0 +initial_quaternion_i2b(2) = 3.0 +initial_quaternion_i2b(3) = 4.0 // Initial torque at body frame [Nm] // Note: The initial torque added just for the first propagation step @@ -34,19 +34,19 @@ initial_torque_b_Nm(2) = 0.000 // EARTH_CENTER_POINTING // VELOCITY_DIRECTION_POINTING // ORBIT_NORMAL_POINTING -main_mode = INERTIAL_STABILIZE -sub_mode = SUN_POINTING +main_mode = SUN_POINTING +sub_mode = INERTIAL_STABILIZE // Pointing direction @ body frame for main pointing mode -main_pointing_direction_b(0) = 1.0 +main_pointing_direction_b(0) = 0.0 main_pointing_direction_b(1) = 0.0 -main_pointing_direction_b(2) = 0.0 +main_pointing_direction_b(2) = 1.0 // Pointing direction @ body frame for sub pointing mode // main_pointing_direction_b and sub_pointing_direction_b should separate larger than 30 degrees. -sub_pointing_direction_b(0) = 0.0 +sub_pointing_direction_b(0) = 1.0 sub_pointing_direction_b(1) = 0.0 -sub_pointing_direction_b(2) = 1.0 +sub_pointing_direction_b(2) = 0.0 [ORBIT] calculation = ENABLE From 776fb4a6f894732c20e44580eaaf2377ed93d857 Mon Sep 17 00:00:00 2001 From: kai0722 <69716740+kai0722@users.noreply.github.com> Date: Tue, 4 Apr 2023 13:24:02 +0900 Subject: [PATCH 1081/1086] Update sample_satellite.ini --- .../initialize_files/sample_satellite.ini | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/data/sample/initialize_files/sample_satellite.ini b/data/sample/initialize_files/sample_satellite.ini index 9853c857c..624f065fd 100644 --- a/data/sample/initialize_files/sample_satellite.ini +++ b/data/sample/initialize_files/sample_satellite.ini @@ -16,10 +16,10 @@ initial_angular_velocity_b_rad_s(2) = 0.0 // Initial quaternion inertial frame to body frame (real part, imaginary part) // This value also used in INERTIAL_STABILIZE mode of ControlledAttitude -initial_quaternion_i2b(0) = 1.0 -initial_quaternion_i2b(1) = 2.0 -initial_quaternion_i2b(2) = 3.0 -initial_quaternion_i2b(3) = 4.0 +initial_quaternion_i2b(0) = 0.0 +initial_quaternion_i2b(1) = 0.0 +initial_quaternion_i2b(2) = 0.0 +initial_quaternion_i2b(3) = 1.0 // Initial torque at body frame [Nm] // Note: The initial torque added just for the first propagation step @@ -34,19 +34,19 @@ initial_torque_b_Nm(2) = 0.000 // EARTH_CENTER_POINTING // VELOCITY_DIRECTION_POINTING // ORBIT_NORMAL_POINTING -main_mode = SUN_POINTING -sub_mode = INERTIAL_STABILIZE +main_mode = INERTIAL_STABILIZE +sub_mode = SUN_POINTING // Pointing direction @ body frame for main pointing mode -main_pointing_direction_b(0) = 0.0 +main_pointing_direction_b(0) = 1.0 main_pointing_direction_b(1) = 0.0 -main_pointing_direction_b(2) = 1.0 +main_pointing_direction_b(2) = 0.0 // Pointing direction @ body frame for sub pointing mode // main_pointing_direction_b and sub_pointing_direction_b should separate larger than 30 degrees. -sub_pointing_direction_b(0) = 1.0 +sub_pointing_direction_b(0) = 0.0 sub_pointing_direction_b(1) = 0.0 -sub_pointing_direction_b(2) = 0.0 +sub_pointing_direction_b(2) = 1.0 [ORBIT] calculation = ENABLE From 1246a88d1807b7bc58aa2409682a63fd305b892a Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 4 Apr 2023 15:05:25 +0200 Subject: [PATCH 1082/1086] Fix interface for Monte Carlo simulation --- .../initialize_files/sample_simulation_base.ini | 16 ++++++++-------- src/dynamics/attitude/attitude.hpp | 2 +- src/dynamics/attitude/attitude_rk4.cpp | 2 +- src/dynamics/attitude/attitude_rk4.hpp | 2 +- src/dynamics/attitude/controlled_attitude.hpp | 2 +- src/dynamics/attitude/initialize_attitude.cpp | 2 +- src/library/logger/initialize_log.cpp | 2 +- 7 files changed, 14 insertions(+), 14 deletions(-) diff --git a/data/sample/initialize_files/sample_simulation_base.ini b/data/sample/initialize_files/sample_simulation_base.ini index 49df9495f..0e052a1ca 100644 --- a/data/sample/initialize_files/sample_simulation_base.ini +++ b/data/sample/initialize_files/sample_simulation_base.ini @@ -65,14 +65,14 @@ attitude0.debug.sigma_or_max(0) = 10.0 attitude0.debug.sigma_or_max(1) = 10.0 attitude0.debug.sigma_or_max(2) = 10.0 -parameter(1) = attitude0.omega_b -attitude0.omega_b.randomization_type = NoRandomization -attitude0.omega_b.mean_or_min(0) = 0.0 -attitude0.omega_b.mean_or_min(1) = 0.0 -attitude0.omega_b.mean_or_min(2) = 0.0 -attitude0.omega_b.sigma_or_max(0) = 0.05817764 // 3-sigma = 10 [deg/s] -attitude0.omega_b.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] -attitude0.omega_b.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] +parameter(1) = attitude0.angular_velocity_b_rad_s +attitude0.angular_velocity_b_rad_s.randomization_type = CartesianUniform +attitude0.angular_velocity_b_rad_s.mean_or_min(0) = 0.0 +attitude0.angular_velocity_b_rad_s.mean_or_min(1) = 0.0 +attitude0.angular_velocity_b_rad_s.mean_or_min(2) = 0.0 +attitude0.angular_velocity_b_rad_s.sigma_or_max(0) = 0.05817764 // 3-sigma = 10 [deg/s] +attitude0.angular_velocity_b_rad_s.sigma_or_max(1) = 0.05817764 // 3-sigma = 10 [deg/s] +attitude0.angular_velocity_b_rad_s.sigma_or_max(2) = 0.05817764 // 3-sigma = 10 [deg/s] [CELESTIAL_INFORMATION] diff --git a/src/dynamics/attitude/attitude.hpp b/src/dynamics/attitude/attitude.hpp index 2670e92ab..18e3a0553 100644 --- a/src/dynamics/attitude/attitude.hpp +++ b/src/dynamics/attitude/attitude.hpp @@ -23,7 +23,7 @@ class Attitude : public ILoggable, public SimulationObject { * @brief Constructor * @param [in] simulation_object_name: Simulation object name for Monte-Carlo simulation */ - Attitude(const std::string& simulation_object_name = "Attitude"); + Attitude(const std::string& simulation_object_name = "attitude"); /** * @fn ~Attitude * @brief Destructor diff --git a/src/dynamics/attitude/attitude_rk4.cpp b/src/dynamics/attitude/attitude_rk4.cpp index b2bc62f67..ff8e6792c 100644 --- a/src/dynamics/attitude/attitude_rk4.cpp +++ b/src/dynamics/attitude/attitude_rk4.cpp @@ -28,7 +28,7 @@ AttitudeRk4::~AttitudeRk4() {} void AttitudeRk4::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { Attitude::SetParameters(mc_simulator); - GetInitializedMonteCarloParameterVector(mc_simulator, "Omega_b", angular_velocity_b_rad_s_); + GetInitializedMonteCarloParameterVector(mc_simulator, "angular_velocity_b_rad_s", angular_velocity_b_rad_s_); // TODO: Consider the following calculation is needed here? current_propagation_time_s_ = 0.0; diff --git a/src/dynamics/attitude/attitude_rk4.hpp b/src/dynamics/attitude/attitude_rk4.hpp index bf838dd1f..b1d4d920a 100644 --- a/src/dynamics/attitude/attitude_rk4.hpp +++ b/src/dynamics/attitude/attitude_rk4.hpp @@ -26,7 +26,7 @@ class AttitudeRk4 : public Attitude { */ AttitudeRk4(const libra::Vector<3>& angular_velocity_b_rad_s, const libra::Quaternion& quaternion_i2b, const libra::Matrix<3, 3>& inertia_tensor_kgm2, const libra::Vector<3>& torque_b_Nm, const double propagation_step_s, - const std::string& simulation_object_name = "Attitude"); + const std::string& simulation_object_name = "attitude"); /** * @fn ~AttitudeRk4 * @brief Destructor diff --git a/src/dynamics/attitude/controlled_attitude.hpp b/src/dynamics/attitude/controlled_attitude.hpp index 8eba9f3b8..f0de70d14 100644 --- a/src/dynamics/attitude/controlled_attitude.hpp +++ b/src/dynamics/attitude/controlled_attitude.hpp @@ -56,7 +56,7 @@ class ControlledAttitude : public Attitude { ControlledAttitude(const AttitudeControlMode main_mode, const AttitudeControlMode sub_mode, const libra::Quaternion quaternion_i2b, const libra::Vector<3> main_target_direction_b, const libra::Vector<3> sub_target_direction_b, const libra::Matrix<3, 3>& inertia_tensor_kgm2, const LocalCelestialInformation* local_celestial_information, const Orbit* orbit, - const std::string& simulation_object_name = "Attitude"); + const std::string& simulation_object_name = "attitude"); /** * @fn ~ControlledAttitude * @brief Destructor diff --git a/src/dynamics/attitude/initialize_attitude.cpp b/src/dynamics/attitude/initialize_attitude.cpp index 0383b8c62..7adf597db 100644 --- a/src/dynamics/attitude/initialize_attitude.cpp +++ b/src/dynamics/attitude/initialize_attitude.cpp @@ -10,7 +10,7 @@ Attitude* InitAttitude(std::string file_name, const Orbit* orbit, const LocalCel const double step_width_s, const libra::Matrix<3, 3> inertia_tensor_kgm2, const int spacecraft_id) { IniAccess ini_file(file_name); const char* section_ = "ATTITUDE"; - std::string mc_name = section_ + std::to_string(spacecraft_id); // FIXME + std::string mc_name = "attitude" + std::to_string(spacecraft_id); Attitude* attitude; const std::string propagate_mode = ini_file.ReadString(section_, "propagate_mode"); diff --git a/src/library/logger/initialize_log.cpp b/src/library/logger/initialize_log.cpp index 598f2f475..74f8b377e 100644 --- a/src/library/logger/initialize_log.cpp +++ b/src/library/logger/initialize_log.cpp @@ -24,7 +24,7 @@ Logger* InitMonteCarloLog(std::string file_name, bool enable) { std::string log_file_path = ini_file.ReadString("SIMULATION_SETTINGS", "log_file_save_directory"); bool log_ini = ini_file.ReadEnable("SIMULATION_SETTINGS", "save_initialize_files"); - Logger* log = new Logger("mont.csv", log_file_path, file_name, log_ini, enable); + Logger* log = new Logger("monte_carlo.csv", log_file_path, file_name, log_ini, enable); return log; } From daad7ec8717438447575b185027a1444871d40f6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 4 Apr 2023 15:06:48 +0200 Subject: [PATCH 1083/1086] Fix interface for Monte Carlo simulation --- src/dynamics/attitude/attitude.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/dynamics/attitude/attitude.cpp b/src/dynamics/attitude/attitude.cpp index 01eabf378..1a3426ebe 100644 --- a/src/dynamics/attitude/attitude.cpp +++ b/src/dynamics/attitude/attitude.cpp @@ -43,7 +43,7 @@ std::string Attitude::GetLogValue() const { } void Attitude::SetParameters(const MonteCarloSimulationExecutor& mc_simulator) { - GetInitializedMonteCarloParameterQuaternion(mc_simulator, "Q_i2b", quaternion_i2b_); + GetInitializedMonteCarloParameterQuaternion(mc_simulator, "quaternion_i2b", quaternion_i2b_); } void Attitude::CalcAngularMomentum(void) { From da06a147d6139f9d328ae16fc9622c1ec0a8e32e Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 4 Apr 2023 16:15:46 +0200 Subject: [PATCH 1084/1086] Modify log output feature for Monte Carlo simulation --- src/library/logger/logger.cpp | 8 ++++---- src/library/logger/logger.hpp | 8 ++++---- src/simulation/case/simulation_case.cpp | 20 +++++++++++++------- 3 files changed, 21 insertions(+), 15 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index a15e64827..48589e367 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -15,11 +15,11 @@ std::vector log_list_; -Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, - const bool enable) { - is_enabled_ = enable; +Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool is_ini_save_enabled, + const bool is_enabled) + : is_enabled_(is_enabled), is_ini_save_enabled_(is_ini_save_enabled) { is_file_opened_ = false; - is_ini_save_enabled_ = enable_ini_file_save; + if (is_enabled_ == false) return; // Get current time to append it to the filename time_t timer = time(NULL); diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 827daa4c2..52811ab11 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -26,11 +26,11 @@ class Logger { * @param [in] file_name: File name of the log output * @param [in] data_path: Path to `data` directory * @param [in] ini_file_name: Initialize file name - * @param [in] enable_ini_file_save: Enable flag to save ini files - * @param [in] enable: Enable flag for logging + * @param [in] is_ini_save_enabled: Enable flag to save ini files + * @param [in] is_enabled: Enable flag for logging */ - Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool enable_ini_file_save, - const bool enable = true); + Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool is_ini_save_enabled, + const bool is_enabled = true); /** * @fn ~Logger * @brief Destructor diff --git a/src/simulation/case/simulation_case.cpp b/src/simulation/case/simulation_case.cpp index 8450d3883..334514a94 100644 --- a/src/simulation/case/simulation_case.cpp +++ b/src/simulation/case/simulation_case.cpp @@ -19,13 +19,19 @@ SimulationCase::SimulationCase(const std::string initialize_base_file) { SimulationCase::SimulationCase(const std::string initialize_base_file, const MonteCarloSimulationExecutor& monte_carlo_simulator, const std::string log_path) { - // Initialize Log - // Log for Monte Carlo Simulation - std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; - // TODO: Consider that `enable_inilog = false` is fine or not? - simulation_configuration_.main_logger_ = - new Logger(log_file_name, log_path, initialize_base_file, false, monte_carlo_simulator.GetSaveLogHistoryFlag()); - + if (monte_carlo_simulator.IsEnabled() == false) { + // Monte Carlo simulation is disabled + simulation_configuration_.main_logger_ = InitLog(initialize_base_file); + } else { + // Monte Carlo Simulation is enabled + std::string log_file_name = "default" + std::to_string(monte_carlo_simulator.GetNumberOfExecutionsDone()) + ".csv"; + + IniAccess ini_file(initialize_base_file); + bool save_ini_files = ini_file.ReadEnable("SIMULATION_SETTINGS", "save_initialize_files"); + + simulation_configuration_.main_logger_ = + new Logger(log_file_name, log_path, initialize_base_file, save_ini_files, monte_carlo_simulator.GetSaveLogHistoryFlag()); + } // Initialize Simulation Configuration InitializeSimulationConfiguration(initialize_base_file); } From 18c00f176665a107840e13bed30cdd52e5bc9b59 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Tue, 4 Apr 2023 16:46:45 +0200 Subject: [PATCH 1085/1086] Add create directory flag --- src/library/logger/logger.cpp | 7 +++++-- src/library/logger/logger.hpp | 1 + 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/library/logger/logger.cpp b/src/library/logger/logger.cpp index 48589e367..2a847b286 100644 --- a/src/library/logger/logger.cpp +++ b/src/library/logger/logger.cpp @@ -14,6 +14,7 @@ #endif std::vector log_list_; +bool Logger::is_directory_created_ = false; Logger::Logger(const std::string &file_name, const std::string &data_path, const std::string &ini_file_name, const bool is_ini_save_enabled, const bool is_enabled) @@ -29,10 +30,11 @@ Logger::Logger(const std::string &file_name, const std::string &data_path, const strftime(start_time_c, 64, "%y%m%d_%H%M%S", now); // Create directory - if (is_ini_save_enabled_ == true) + if (is_ini_save_enabled_ == true || is_directory_created_ == false) { directory_path_ = CreateDirectory(data_path, start_time_c); - else + } else { directory_path_ = data_path; + } // Create File std::stringstream file_path; file_path << directory_path_ << start_time_c << "_" << file_name; @@ -94,6 +96,7 @@ std::string Logger::CreateDirectory(const std::string &data_path, const std::str std::cerr << "Error making directory: " << directory_path_tmp_ << std::endl; return data_path; } + is_directory_created_ = true; return directory_path_tmp_; } diff --git a/src/library/logger/logger.hpp b/src/library/logger/logger.hpp index 52811ab11..375f76962 100644 --- a/src/library/logger/logger.hpp +++ b/src/library/logger/logger.hpp @@ -90,6 +90,7 @@ class Logger { std::ofstream csv_file_; //!< CSV file stream bool is_enabled_; //!< Enable flag for logging bool is_file_opened_; //!< Is the CSV file opened? + static bool is_directory_created_; //!< Is the log output directory is created in the scenario std::vector log_list_; //!< Log list bool is_ini_save_enabled_; //!< Enable flag to save ini files From ea4a6a9f868c292d24cbcd46536cd166934786e6 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Thu, 6 Apr 2023 08:01:33 +0200 Subject: [PATCH 1086/1086] Remove old include directory --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index dd99ab26b..4c2a9f245 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,7 +41,6 @@ if(USE_C2A) add_definitions(-DSILS_FW) #include_directories include_directories(${C2A_DIR}/src) - include_directories(${S2E_CORE_DIR}/src/interface/sils) #add subdirectory add_subdirectory(${C2A_DIR} C2A) endif()