diff --git a/C2A_AOBC.vcxproj b/C2A_AOBC.vcxproj
index 583c7539..86f0a581 100644
--- a/C2A_AOBC.vcxproj
+++ b/C2A_AOBC.vcxproj
@@ -309,7 +309,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Examples/C2A_AOBC_EXAMPLE.vcxproj b/Examples/C2A_AOBC_EXAMPLE.vcxproj
index e666e395..28a048b5 100644
--- a/Examples/C2A_AOBC_EXAMPLE.vcxproj
+++ b/Examples/C2A_AOBC_EXAMPLE.vcxproj
@@ -316,6 +316,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Examples/CMakeLists.txt b/Examples/CMakeLists.txt
index 20fa512e..f72c35b8 100644
--- a/Examples/CMakeLists.txt
+++ b/Examples/CMakeLists.txt
@@ -19,6 +19,8 @@ option(USE_SCI_COM_UART "Use SCI_COM_UART" OFF)
set(C2A_CORE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/src_aobc/src/src_core)
set(C2A_USER_DIR ${CMAKE_CURRENT_SOURCE_DIR}/src_aobc/src/src_user)
+set(C2A_SATELLITE_PARAMETERS_DIR ../../../../src_aobc_example/Settings/SatelliteParameters/) # relative path from Settings
+add_definitions(-DUSER_DEFINED_I2C_ADDRESS)
set(USE_ALL_C2A_CORE_APPS OFF)
set(USE_ALL_C2A_CORE_TEST_APPS OFF)
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_control_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_control_parameters.c
new file mode 100644
index 00000000..535dbc05
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_control_parameters.c
@@ -0,0 +1,93 @@
+/**
+ * @file attitude_control_parameters.c
+ * @brief 姿勢制御関連の衛星固有パラメータを管理する
+ */
+
+#include
+#include
+
+// Bdot
+const float ATTITUDE_CONTROL_PARAMETERS_bdot_control_gain[PHYSICAL_CONST_THREE_DIM] = { -0.1f, -0.1f, -0.1f };
+const uint32_t ATTITUDE_CONTROL_PARAMETERS_bdot_minimum_time_derivative_step_ms = 100;
+const uint32_t ATTITUDE_CONTROL_PARAMETERS_bdot_mtq_output_time_length_ms = 1000;
+
+// Sun Pointing
+const SUN_POINTING_AXIS_ID ATTITUDE_CONTROL_PARAMETERS_sun_pointing_axis_id = SUN_POINTING_AXIS_ID_Z;
+// Gain
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_x = { 5.0e-5f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_y = { 10.0e-5f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_z = { 0.0f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_x = { 1.0e-2f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_y = { 2.0e-2f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_z = { 7.0e-3f, 0.0f, 2.0e-2f };
+// MTQ control settings
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(20.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_rate_rad_s = 1.6e-3f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_transient = 0.6f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_transient = 0.0f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_stable = 0.8f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_stable = 0.25f;
+// Integral control setting
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_integral_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(20.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_angle_to_run_integral_control_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(30.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_integral_control_permission_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(40.0f);
+// Spin control setting
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_acceptable_angle_error_to_spin_up_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(30.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_spin_rate_around_sun_rad_s = 1.4e-2f;
+// Low Pass Filter setting
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_sample_freq_Hz = 10.0f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_Hz = 0.10f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_damping_factor = 1.0f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_spin_axis_Hz = 0.03f;
+const float ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_spin_rate_cutoff_freq_Hz = 5e-4f;
+
+// Three Axis Control with MTQ
+// Gain
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_x = { 1.2e-4f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_y = { 2.0f * 1.2e-4f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_z = { 1.5f * 1.2e-4f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_x = { 2.5e-2f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_y = { 2.0f * 2.5e-2f, 0.0f, 0.0f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_z = { 1.5f * 2.5e-2f, 0.0f, 0.0f };
+// MTQ control settings
+// 下記の値はISS軌道を想定した値, 変更時は,HW側の出力最大値にかからない様に留意しながら,ゲインと組み合わせて調整すること.
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(18.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_rate_rad_s = 5.0e-3f;
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_transient = 0.6f;
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_transient = 0.0f;
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_stable = 0.6f;
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_stable = 0.1f;
+const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_acceptable_angle_error_as_stable_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(20.0f);
+// Integral control setting
+extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_integral_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(40.0f);
+extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_angle_to_run_integral_control_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(30.0f);
+// Output torque Low Pass Filter(LPF) setting
+extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_sample_freq_Hz = 10.0f;
+extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_cutoff_freq_Hz = 0.3f;
+extern const float ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_damping_factor = 1.0f;
+
+// Three Axis Control with MTQ
+// Gain
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_x = { 1.0e-3f, 0.0f, 1.0e-3f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_y = { 2.0f * 1.0e-3f, 0.0f, 2.0f * 1.0e-3f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_z = { 2.0f * 1.0e-3f, 0.0f, 2.0f * 1.0e-3f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_x = { 7.0e-2f, 0.0f, 2.0e-3f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_y = { 2.0f * 7.0e-2f, 0.0f, 2.0f * 2.0e-3f };
+const PidGains ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_z = { 2.0f * 7.0e-2f, 0.0f, 2.0f * 2.0e-3f };
+
+// Unloading
+const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_upper_threshold_rad_s = PARAMETER_SETTING_MACRO_RPM_TO_RADIAN_SEC(7000.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_lower_threshold_rad_s = PARAMETER_SETTING_MACRO_RPM_TO_RADIAN_SEC(-7000.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_target_rad_s = PARAMETER_SETTING_MACRO_RPM_TO_RADIAN_SEC(0.0f);
+const float ATTITUDE_CONTROL_PARAMETERS_unloading_control_gain = -1.0e-7f;
+const APP_UNLOADING_EXEC ATTITUDE_CONTROL_PARAMETERS_unloading_exec_is_enable = APP_UNLOADING_EXEC_DISABLE;
+
+// Control Torques
+const AOCS_MANAGER_CONSTANT_TORQUE_PERMISSION ATTITUDE_CONTROL_PARAMETERS_constant_torque_permission = AOCS_MANAGER_CONSTANT_TORQUE_DISABLE;
+const float ATTITUDE_CONTROL_PARAMETERS_constant_torque_body_Nm[PHYSICAL_CONST_THREE_DIM] = { 0.0f, 0.0f, 0.0f };
+const float ATTITUDE_CONTROL_PARAMETERS_internal_torque_max_body_Nm[PHYSICAL_CONST_THREE_DIM] = { 5.0e-3f, 5.0e-3f, 5.0e-3f };
+const float ATTITUDE_CONTROL_PARAMETERS_external_torque_max_body_Nm[PHYSICAL_CONST_THREE_DIM] = { 3.0e-4f, 3.0e-4f, 3.0e-4f };
+
+// Target Setting parameters
+const float ATTITUDE_CONTROL_PARAMETERS_limit_angular_velocity_rad_s = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(0.8f);
+const float ATTITUDE_CONTROL_PARAMETERS_limit_maneuver_angle_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(30.0f);
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_determination_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_determination_parameters.c
new file mode 100644
index 00000000..7e746566
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_determination_parameters.c
@@ -0,0 +1,42 @@
+/**
+ * @file attitude_determination_parameters.c
+ * @brief 姿勢決定系に関する衛星固有パラメータを管理する
+ */
+
+#include
+#include
+#include
+
+// Rough Three Axis Determination
+const APP_RTAD_METHOD ATTITUDE_DETERMINATION_PARAMETERS_rtad_method = APP_RTAD_METHOD_TRIAD;
+const float ATTITUDE_DETERMINATION_PARAMETERS_q_method_sun_vec_weight = 0.5f;
+
+// Fine Three Axis Determination
+const APP_FTAD_METHOD ATTITUDE_DETERMINATION_PARAMETERS_ftad_method = APP_FTAD_METHOD_STT;
+
+// STT-Gyro Extended Kalman Filter
+// STIM210 random noise N = 15deg/sq(h)
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_noise_standard_deviation_compo_rad_s[PHYSICAL_CONST_THREE_DIM] = { 4.363323e-5f,
+ 4.363323e-5f,
+ 4.363323e-5f };
+// STIM210 bias stability B = 0.3deg/h, K=3/2*B^2/N
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_standard_deviation_compo_rad_s2[PHYSICAL_CONST_THREE_DIM] = { 7.272205e-8f,
+ 7.272205e-8f,
+ 7.272205e-8f };
+// As result of sensor feature measurement, STIM210 noise looks a simple random walk model.
+// When ECRV time constant is infinite, the model is same as a simple random walk, so we set very large value here.
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_time_constant_s = 1e9f;
+
+// STT noise roll direction 10 arcsec, cross direction 2 arcsec
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_stt_standard_deviation_compo_rad[PHYSICAL_CONST_THREE_DIM] = { 4.8481e-5f,
+ 9.6963e-6f,
+ 9.6963e-6f };
+// Process noise model
+// We assume the attitude target is operated to synchronize with orbit.
+#define ATTITUDE_PARAMETER_ORBIT_PERIOD_SEC (5700.0f)
+#define ATTITUDE_PARAMETER_COMPUTATION_CYCLE_SEC (0.1f)
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude = ((MATH_CONST_2PI / ATTITUDE_PARAMETER_ORBIT_PERIOD_SEC * ATTITUDE_PARAMETER_COMPUTATION_CYCLE_SEC))
+ * ((MATH_CONST_2PI / ATTITUDE_PARAMETER_ORBIT_PERIOD_SEC * ATTITUDE_PARAMETER_COMPUTATION_CYCLE_SEC));
+// The attitude rate process noise is not well tuned at this moment
+const float ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude_rate = ((MATH_CONST_2PI / ATTITUDE_PARAMETER_ORBIT_PERIOD_SEC * ATTITUDE_PARAMETER_COMPUTATION_CYCLE_SEC))
+ * ((MATH_CONST_2PI / ATTITUDE_PARAMETER_ORBIT_PERIOD_SEC * ATTITUDE_PARAMETER_COMPUTATION_CYCLE_SEC));
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_target_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_target_parameters.c
new file mode 100644
index 00000000..8599e62b
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/attitude_target_parameters.c
@@ -0,0 +1,28 @@
+/**
+ * @file attitude_target_parameters.c
+ * @brief 姿勢目標の衛星固有パラメータを管理する
+ */
+
+#include
+#include
+
+// Target Calculation Mode
+const APP_TARGET_ATT_CALC_MODE ATTITUDE_TARGET_PARAMETERS_mode = APP_TARGET_ATT_CALC_MODE_MANUAL;
+
+// Manual mode target
+const Quaternion ATTITUDE_TARGET_PARAMETERS_quaternion_target_i2t = { 0.5f, 0.5f, 0.5f, 0.5f };
+
+// Target calculation from orbit
+// Main target
+extern const APP_TAFO_TARGET_DIRECITON ATTITUDE_TARGET_PARAMETERS_main_target_direction = APP_TAFO_TARGET_DIRECITON_SUN;
+extern const float ATTITUDE_TARGET_PARAMETERS_vec_to_main_target_body[PHYSICAL_CONST_THREE_DIM] = { 1.0f, 0.0f, 0.0f };
+// Sub target
+extern const APP_TAFO_TARGET_DIRECITON ATTITUDE_TARGET_PARAMETERS_sub_target_direction = APP_TAFO_TARGET_DIRECITON_EARTH_CENTER;
+extern const float ATTITUDE_TARGET_PARAMETERS_vec_to_sub_target_body[PHYSICAL_CONST_THREE_DIM] = { 0.0f, 1.0f, 0.0f };
+// Offset angle
+extern const MATRIX33_ROTATION_AXIS ATTITUDE_TARGET_PARAMETERS_offset_angle_axis = MATRIX33_ROTATION_AXIS_X;
+extern const float ATTITUDE_TARGET_PARAMETERS_offset_angle_rad = 0.0f;
+// Target on earth surface
+extern const float ATTITUDE_TARGET_PARAMETERS_target_lla_rad_m[PHYSICAL_CONST_THREE_DIM] = { PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(35.7130f),
+ PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(139.7596f),
+ 23.0f };
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/component_selector_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/component_selector_parameters.c
new file mode 100644
index 00000000..4c87628d
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/component_selector_parameters.c
@@ -0,0 +1,8 @@
+/**
+ * @file component_selector_parameters.c
+ * @brief コンポセレクタに関する衛星固有パラメータを管理する
+ */
+
+#include
+
+const APP_MAG_SELECTOR_STATE COMPONENT_SELECTOR_PARAMETERS_initial_selected_magnetometer = APP_MAG_SELECTOR_STATE_RM_EXT;
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/fdir_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/fdir_parameters.c
new file mode 100644
index 00000000..e1d326a9
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/fdir_parameters.c
@@ -0,0 +1,183 @@
+/**
+ * @file fdir_parameters.c
+ * @brief FDIRに関する衛星固有パラメータを管理する
+ */
+
+#include
+#include
+
+// Mode Manager
+// Bdot
+const float FDIR_PARAMETERS_ang_vel_conv_limit_rad_s = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(0.5f);
+const float FDIR_PARAMETERS_ang_vel_conv_time_limit_s = 5.0f * 60.0f;
+const float FDIR_PARAMETERS_ang_vel_norm_increase_limit_rad_s = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(0.5f);
+const float FDIR_PARAMETERS_ang_vel_anomaly_detection_period_s = 200.0f;
+const uint32_t FDIR_PARAMETERS_bdot_start_mode_manager_time_s = 5 * 60;
+// Sun pointing control divergence anomaly
+const float FDIR_PARAMETERS_sun_angle_div_limit_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(45.0f);
+const float FDIR_PARAMETERS_sun_angle_div_time_limit_s = 50.0f * 60.0f;
+const uint32_t FDIR_PARAMETERS_sun_pointing_start_mode_manager_time_s = 25 * 60;
+// Rough three axis control with MTQ divergence anomaly
+const float FDIR_PARAMETERS_rough_three_axis_mtq_div_limit_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(30.0f);
+const float FDIR_PARAMETERS_rough_three_axis_mtq_div_time_limit_s = 5.0f * 60.0f;
+const uint32_t FDIR_PARAMETERS_rough_three_axis_mtq_start_mode_manager_time_s = 35 * 60;
+// Rough three axis control with RW divergence anomaly
+const float FDIR_PARAMETERS_rough_three_axis_rw_div_limit_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(10.0f);
+const float FDIR_PARAMETERS_rough_three_axis_rw_div_time_limit_s = 1.0f * 60.0f;
+const uint32_t FDIR_PARAMETERS_rough_three_axis_rw_start_mode_manager_time_s = 5 * 60;
+// Fine three axis control divergence anomaly
+const float FDIR_PARAMETERS_fine_three_axis_div_limit_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(5.0f);
+const float FDIR_PARAMETERS_fine_three_axis_div_time_limit_s = 1.0f * 60.0f;
+const uint32_t FDIR_PARAMETERS_fine_three_axis_start_mode_manager_time_s = 5 * 60;
+// Sensor invisible anomaly
+const float FDIR_PARAMETERS_sun_invisible_time_limit_s = 50.0f * 60.0f;
+const float FDIR_PARAMETERS_stt_invisible_time_limit_s = 10.0f * 60.0f;
+
+
+// S/W over current detection
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_pic_mA = 200;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_stim210_mA = 1000;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_sagitta_mA = 500;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_oem7600_mA = 1000;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rm3100_mA = 200;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_nanossoc_d60_mA = 150;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_mtq_mA = 2000;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_x_mA = 2000;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_y_mA = 2000;
+const uint16_t FDIR_PARAMETERS_sw_oc_threshold_rw0003_z_mA = 2000;
+// Event handler settings
+// STIM210
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_stim210 = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_stim210_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_stim210 = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_stim210_ms = 0;
+// Sagitta
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_sagitta = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_sagitta_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_sagitta = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_sagitta_ms = 0;
+// OEM7600
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_oem7600 = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_oem7600_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_oem7600 = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_oem7600_ms = 0;
+// RM3100
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rm3100 = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rm3100_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rm3100 = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rm3100_ms = 0;
+// nanoSSOC D60
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_nanossoc_d60 = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_nanossoc_d60_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_nanossoc_d60 = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_nanossoc_d60_ms = 0;
+// MTQ
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_mtq = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_mtq_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_mtq = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_mtq_ms = 0;
+// RW
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_x = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_x_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_x = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_x_ms = 0;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_y = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_y_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_y = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_y_ms = 0;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_reset_count_threshold_rw0003_z = 10;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_reset_time_threshold_rw0003_z_ms = 5000;
+const uint16_t FDIR_PARAMETERS_sw_oc_eh_power_off_count_threshold_rw0003_z = 5;
+const uint32_t FDIR_PARAMETERS_sw_oc_eh_power_off_time_threshold_rw0003_z_ms = 0;
+
+
+// H/W over current detection
+// If the measured voltage is smaller than the following values, we assume that the H/W OC protection was executed by the INA260.
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_pic_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_stim210_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_sagitta_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_oem7600_V = 1.0f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_rm3100_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_nanossoc_d60_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_mtq_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_x_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_y_V = 0.5f;
+const float FDIR_PARAMETERS_hw_oc_detection_threshold_rw0003_z_V = 0.5f;
+// Event handler settings
+// STIM210
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_stim210 = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_stim210_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_stim210 = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_stim210_ms = 0;
+// Sagitta
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_sagitta = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_sagitta_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_sagitta = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_sagitta_ms = 0;
+// OEM7600
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_oem7600 = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_oem7600_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_oem7600 = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_oem7600_ms = 0;
+// RM3100
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rm3100 = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rm3100_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rm3100 = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rm3100_ms = 0;
+// nanoSSOC D60
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_nanossoc_d60 = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_nanossoc_d60_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_nanossoc_d60 = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_nanossoc_d60_ms = 0;
+// MTQ
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_mtq = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_mtq_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_mtq = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_mtq_ms = 0;
+// RW
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_x = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_x_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_x = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_x_ms = 0;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_y = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_y_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_y = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_y_ms = 0;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_reset_count_threshold_rw0003_z = 10;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_reset_time_threshold_rw0003_z_ms = 5000;
+const uint16_t FDIR_PARAMETERS_hw_oc_eh_power_off_count_threshold_rw0003_z = 5;
+const uint32_t FDIR_PARAMETERS_hw_oc_eh_power_off_time_threshold_rw0003_z_ms = 0;
+
+// Telemetry anomaly
+// MPU9250
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_mp9250 = 100;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_mp9250_ms = 2000;
+// RM3100
+// Use same value for all RM3100s (Users can also change the value with command for each RM3100)
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rm3100 = 1000;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rm3100_ms = 2000;
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_rm3100 = 10;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_rm3100_ms = 0;
+// nanoSSOC D60
+// Use same value for all sun sensors (Users can also change the value with command for each sun sensors)
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_nanossoc_d60 = 250;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_nanossoc_d60_ms = 2000;
+// STIM210
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_stim210 = 100;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_stim210_ms = 2000;
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_count_threshold_stim210 = 5;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_switch_sensor_time_threshold_stim210_ms = 0;
+// Sagitta
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_sagitta = 100;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_sagitta_ms = 2000;
+// OEM7600
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_oem7600 = 100;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_oem7600_ms = 1000;
+// RW0003
+// Use same value for all RWs (Users can also change the value with command for each RW)
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_rw0003 = 10;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_rw0003_ms = 2000;
+// INA260
+// Use same value for all current sensors (Users can also change the value with command for each current sensor)
+const uint16_t FDIR_PARAMETERS_tlm_error_eh_reset_count_threshold_ina260 = 100;
+const uint32_t FDIR_PARAMETERS_tlm_error_eh_reset_time_threshold_ina260_ms = 5000;
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/ina260_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/ina260_parameters.c
new file mode 100644
index 00000000..49dce5a4
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/ina260_parameters.c
@@ -0,0 +1,66 @@
+/**
+ * @file ina260_parameters.c
+ * @brief INA260に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// PIC
+const INA260_AVERAGING_MODE INA260_PARAMETERS_pic_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_pic_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_pic_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_pic_hw_over_current_threshold_mA = 200.0f;
+
+// STIM210
+const INA260_AVERAGING_MODE INA260_PARAMETERS_stim210_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_stim210_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_stim210_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_stim210_hw_over_current_threshold_mA = 1000.0f;
+
+// SAGITTA
+const INA260_AVERAGING_MODE INA260_PARAMETERS_sagitta_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_sagitta_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_sagitta_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_sagitta_hw_over_current_threshold_mA = 500.0f;
+
+// OEM7600
+const INA260_AVERAGING_MODE INA260_PARAMETERS_oem7600_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_oem7600_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_oem7600_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_oem7600_hw_over_current_threshold_mA = 1000.0f;
+
+// RM3100
+const INA260_AVERAGING_MODE INA260_PARAMETERS_rm3100_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rm3100_voltage_conversion_time = INA260_CONVERSION_TIME_1MS;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rm3100_current_conversion_time = INA260_CONVERSION_TIME_1MS;
+const float INA260_PARAMETERS_rm3100_hw_over_current_threshold_mA = 200.0f;
+
+// NanoSSOC-D60
+const INA260_AVERAGING_MODE INA260_PARAMETERS_nanossoc_d60_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_nanossoc_d60_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_nanossoc_d60_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_nanossoc_d60_hw_over_current_threshold_mA = 150.0f;
+
+// MTQ
+const INA260_AVERAGING_MODE INA260_PARAMETERS_mtq_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_mtq_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_mtq_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_mtq_hw_over_current_threshold_mA = 2000.0f;
+
+// RW0003 X
+const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_x_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_x_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_x_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_rw0003_x_hw_over_current_threshold_mA = 2000.0f;
+
+// RW0003 Y
+const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_y_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_y_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_y_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_rw0003_y_hw_over_current_threshold_mA = 2000.0f;
+
+// RW0003 Z
+const INA260_AVERAGING_MODE INA260_PARAMETERS_rw0003_z_averaging_mode = INA260_AVERAGING_MODE_16;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_z_voltage_conversion_time = INA260_CONVERSION_TIME_140US;
+const INA260_CONVERSION_TIME INA260_PARAMETERS_rw0003_z_current_conversion_time = INA260_CONVERSION_TIME_140US;
+const float INA260_PARAMETERS_rw0003_z_hw_over_current_threshold_mA = 2000.0f;
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/mpu9250_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/mpu9250_parameters.c
new file mode 100644
index 00000000..fede6c2c
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/mpu9250_parameters.c
@@ -0,0 +1,41 @@
+/**
+ * @file mpu9250_parameters.c
+ * @brief MPU9250に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// Communication port
+
+// Magnetometer bias
+// The following parameter should be tuned with magnetic experiment
+const float MPU9250_PARAMETERS_mag_bias_compo_nT[PHYSICAL_CONST_THREE_DIM] = { -18417.53f, -30423.31f, 20969.18f };
+
+// Gyro Bias and scale factor temperature calibration
+const float MPU9250_PARAMETERS_temperature_range_high_degC = 60.0f;
+const float MPU9250_PARAMETERS_temperature_range_low_degC = -50.0f;
+// The following parameters should be tuned with temperature experiment results
+const float MPU9250_PARAMETERS_bias_coeff_compo_x[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { -0.024f, 0.0002f };
+const float MPU9250_PARAMETERS_scale_factor_coeff_compo_x[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+const float MPU9250_PARAMETERS_bias_coeff_compo_y[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { 0.0058f, -0.0005f };
+const float MPU9250_PARAMETERS_scale_factor_coeff_compo_y[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+const float MPU9250_PARAMETERS_bias_coeff_compo_z[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { 0.0179f, 0.0001f };
+const float MPU9250_PARAMETERS_scale_factor_coeff_compo_z[MPU9250_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+
+// Magnetometer filter
+// 1st order Low Pass Filter
+const float MPU9250_PARAMETERS_mag_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM] = { 0.5f, 0.5f, 0.5f };
+// Spike filter
+const uint8_t MPU9250_PARAMETERS_mag_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = { 3, 3, 3 };
+const uint8_t MPU9250_PARAMETERS_mag_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = { 60, 60, 60 };
+const float MPU9250_PARAMETERS_mag_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM] = { 5000.0f, 5000.0f, 5000.0f };
+const float MPU9250_PARAMETERS_mag_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM] = { 1500.0f, 1500.0f, 1500.0f };
+
+// Gyro filter
+// 1st order Low Pass Filter
+const float MPU9250_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM] = { 0.05f, 0.05f, 0.05f };
+// Spike filter
+const uint8_t MPU9250_PARAMETERS_gyro_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = { 3, 3, 3 };
+const uint8_t MPU9250_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = { 60, 60, 60 };
+const float MPU9250_PARAMETERS_gyro_spike_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM] = { 0.01f, 0.01f, 0.01f };
+const float MPU9250_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM] = { 0.005f, 0.005f, 0.005f };
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/nanossoc_d60_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/nanossoc_d60_parameters.c
new file mode 100644
index 00000000..fcccd4b6
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/nanossoc_d60_parameters.c
@@ -0,0 +1,23 @@
+/**
+ * @file nanossoc_d60_parameters.c
+ * @brief nanossoc-D60に関する衛星固有パラメータを管理する
+ */
+
+#include
+#include
+
+// Frame conversion
+const Quaternion NANOSSOC_D60_PARAMETERS_py_quaternion_c2b = { 0.70710665f, 0.0f, 0.0f, 0.70710665f };
+const Quaternion NANOSSOC_D60_PARAMETERS_my_quaternion_c2b = { 0.0f, -0.70710665f, 0.70710665f, 0.0f };
+const Quaternion NANOSSOC_D60_PARAMETERS_pz_quaternion_c2b = { 0.0f, 0.0f, 0.70710665f, 0.70710665f };
+const Quaternion NANOSSOC_D60_PARAMETERS_mz_quaternion_c2b = { -0.707106471f, 0.707106471f, 0.0f, 0.0f };
+
+// Spike Filter
+uint8_t NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_accept = 10;
+uint8_t NANOSSOC_D60_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning = 60;
+float NANOSSOC_D60_PARAMETERS_spike_filter_config_reject_threshold_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(3);
+float NANOSSOC_D60_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(180);
+
+// Sun intensity threshold
+float NANOSSOC_D60_PARAMETERS_sun_intensity_lower_threshold_percent = 80.0f;
+float NANOSSOC_D60_PARAMETERS_sun_intensity_upper_threshold_percent = 120.0f;
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/oem7600_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/oem7600_parameters.c
new file mode 100644
index 00000000..e14ee8f2
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/oem7600_parameters.c
@@ -0,0 +1,19 @@
+/**
+ * @file oem7600_parameters.c
+ * @brief OEM7600に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// Spike Filter
+uint8_t OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = {3, 3, 3};
+uint8_t OEM7600_PARAMETERS_position_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = {60, 60, 60};
+double OEM7600_PARAMETERS_position_spike_filter_config_reject_threshold_m[PHYSICAL_CONST_THREE_DIM] = {10000.0, 10000.0, 10000.0};
+double OEM7600_PARAMETERS_position_spike_filter_config_amplitude_limit_to_accept_as_step_m[PHYSICAL_CONST_THREE_DIM] = {8000.0, 8000.0, 8000.0};
+
+uint8_t OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = {3, 3, 3};
+uint8_t OEM7600_PARAMETERS_velocity_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = {60, 60, 60};
+double OEM7600_PARAMETERS_velocity_spike_filter_config_reject_threshold_m_s[PHYSICAL_CONST_THREE_DIM] = {1000.0, 1000.0, 1000.0};
+double OEM7600_PARAMETERS_velocity_spike_filter_config_amplitude_limit_to_accept_as_step_m_s[PHYSICAL_CONST_THREE_DIM] = {100.0, 100.0, 100.0};
+
+// Sun intensity threshold
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/orbit_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/orbit_parameters.c
new file mode 100644
index 00000000..29bc19ee
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/orbit_parameters.c
@@ -0,0 +1,51 @@
+/**
+ * @file orbit_parameters.c
+ * @brief 軌道・時刻関連の衛星固有パラメータを管理する
+ */
+
+#include
+#include
+#include
+
+// Time
+const double ORBIT_PARAMETERS_reference_jday = 2459932.000; // 2022/12/18 12:00:00
+
+// Orbit Calculator
+const APP_ORBIT_CALC_METHOD ORBIT_PARAMETERS_orbit_calculation_method = APP_ORBIT_CALC_METHOD_KEPLER;
+
+// Kepler Orbit
+const float ORBIT_PARAMETERS_kepler_semi_major_axis_km = 6899.3234f;
+const float ORBIT_PARAMETERS_kepler_eccentricity = 4.86396e-4f;
+const float ORBIT_PARAMETERS_kepler_inclination_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(97.50372f);
+const float ORBIT_PARAMETERS_kepler_raan_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(340.20189f);
+const float ORBIT_PARAMETERS_kepler_arg_perigee_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(221.60537f);
+const double ORBIT_PARAMETERS_kepler_epoch_jday = 2.459931936719433e6;
+
+// TLE for SGP4
+// 1st line
+const uint8_t ORBIT_PARAMETERS_tle_epoch_year = 22;
+const double ORBIT_PARAMETERS_tle_epoch_day = 352.00000000;
+const float ORBIT_PARAMETERS_tle_b_star = 0.0;
+// 2nd line
+const float ORBIT_PARAMETERS_tle_inclination_deg = 97.5068f;
+const float ORBIT_PARAMETERS_tle_raan_deg = 339.7118f;
+const float ORBIT_PARAMETERS_tle_eccentricity = 0.0011775f;
+const float ORBIT_PARAMETERS_tle_arg_perigee_deg = 245.9837f;
+const float ORBIT_PARAMETERS_tle_mean_anomaly_deg = 114.0163f;
+const float ORBIT_PARAMETERS_tle_mean_motion_rpd = 15.15782335f;
+
+// GPS-R Orbit Propagator
+// Initial orbital elements
+const float ORBIT_PARAMETERS_gpsr_semi_major_axis_km = 6899.3234f;
+const float ORBIT_PARAMETERS_gpsr_eccentricity = 4.86396e-4f;
+const float ORBIT_PARAMETERS_gpsr_inclination_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(97.50372f);
+const float ORBIT_PARAMETERS_gpsr_raan_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(340.20189f);
+const float ORBIT_PARAMETERS_gpsr_arg_perigee_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(0.0f);
+const double ORBIT_PARAMETERS_gpsr_epoch_jday = 2.459931936719433e6;
+// Threshold
+const float ORBIT_PARAMETERS_gpsr_threshold_semi_major_axis_km = 50.0f;
+const float ORBIT_PARAMETERS_gpsr_threshold_eccentricity = 0.1f;
+const float ORBIT_PARAMETERS_gpsr_threshold_inclination_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(20.0f);
+const float ORBIT_PARAMETERS_gpsr_threshold_raan_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(20.0f);
+const float ORBIT_PARAMETERS_gpsr_threshold_arg_perigee_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(50.0f);
+const double ORBIT_PARAMETERS_gpsr_threshold_epoch_jday = 0.1;
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/rm3100_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/rm3100_parameters.c
new file mode 100644
index 00000000..7439e422
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/rm3100_parameters.c
@@ -0,0 +1,38 @@
+/**
+ * @file rm3100_parameters.c
+ * @brief RM3100に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// AOBC RM3100
+// Magnetometer bias
+// The following parameter should be tuned with magnetic experiment
+const float RM3100_PARAMETERS_mag_aobc_bias_compo_nT[PHYSICAL_CONST_THREE_DIM] = { 32808.59f, -79748.68f, 22059.96f };
+
+// Magnetometer filter
+// 1st order Low Pass Filter
+const float RM3100_PARAMETERS_mag_aobc_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM] = { 0.5f, 0.5f, 0.5f };
+// Spike filter
+const uint8_t RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = { 3, 3, 3 };
+const uint8_t RM3100_PARAMETERS_mag_aobc_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = { 60, 60, 60 };
+const float RM3100_PARAMETERS_mag_aobc_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM] = { 5000.0f, 5000.0f, 5000.0f };
+const float RM3100_PARAMETERS_mag_aobc_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM] = { 1500.0f, 1500.0f, 1500.0f };
+
+
+// External RM3100
+// Frame conversion
+const Quaternion RM3100_PARAMETERS_mag_ext_quaternion_c2b = {-0.707106471, 0.707107127, 0.0f, 0.0f};
+
+// Magnetometer bias
+// The following parameter should be tuned with magnetic experiment
+const float RM3100_PARAMETERS_mag_ext_bias_compo_nT[PHYSICAL_CONST_THREE_DIM] = { 36824.97f, -4596.48f, -1133.40f };
+
+// Magnetometer filter
+// 1st order Low Pass Filter
+const float RM3100_PARAMETERS_mag_ext_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM] = { 0.5f, 0.5f, 0.5f };
+// Spike filter
+const uint8_t RM3100_PARAMETERS_mag_ext_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = { 3, 3, 3 };
+const uint8_t RM3100_PARAMETERS_mag_ext_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = { 60, 60, 60 };
+const float RM3100_PARAMETERS_mag_ext_spike_reject_threshold_nT[PHYSICAL_CONST_THREE_DIM] = { 5000.0f, 5000.0f, 5000.0f };
+const float RM3100_PARAMETERS_mag_ext_spike_amplitude_limit_to_accept_as_step_nT[PHYSICAL_CONST_THREE_DIM] = { 1500.0f, 1500.0f, 1500.0f };
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/rw0003_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/rw0003_parameters.c
new file mode 100644
index 00000000..61bcfda9
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/rw0003_parameters.c
@@ -0,0 +1,12 @@
+/**
+ * @file rw0003_parameters.c
+ * @brief RW.0003に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// Spike Filter
+uint8_t RW0003_PARAMETERS_spike_filter_config_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = {3, 3, 3};
+uint8_t RW0003_PARAMETERS_spike_filter_config_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = {10, 10, 10};
+double RW0003_PARAMETERS_spike_filter_config_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM] = {50.0, 50.0, 50.0};
+double RW0003_PARAMETERS_spike_filter_config_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM] = {25.0, 25.0, 25.0};
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/sagitta_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/sagitta_parameters.c
new file mode 100644
index 00000000..9cd7c3b8
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/sagitta_parameters.c
@@ -0,0 +1,15 @@
+/**
+ * @file sagitta_parameters.c
+ * @brief Sagittaに関する衛星固有パラメータを管理する
+ */
+
+#include
+#include
+
+// Spike Filter
+uint8_t SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_accept = 20;
+uint8_t SAGITTA_PARAMETERS_q_i2b_spike_filter_config_count_limit_to_reject_continued_warning = 200;
+double SAGITTA_PARAMETERS_q_i2b_spike_filter_config_reject_threshold_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(1.0f);
+double SAGITTA_PARAMETERS_q_i2b_spike_filter_config_amplitude_limit_to_accept_as_step_rad = PARAMETER_SETTING_MACRO_DEGREE_TO_RADIAN(0.6f);
+
+// Sun intensity threshold
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/stim210_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/stim210_parameters.c
new file mode 100644
index 00000000..50e0172c
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/stim210_parameters.c
@@ -0,0 +1,30 @@
+/**
+ * @file stim210_parameters.c
+ * @brief STIM210に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+// Gyro constant bias
+// The following parameter should be tuned with experiment
+const float STIM210_PARAMETERS_ang_vel_bias_compo_rad_s[PHYSICAL_CONST_THREE_DIM] = { -2.27E-04f, 2.80E-04f, -3.37E-04f };
+
+// Gyro Bias and scale factor temperature calibration
+const float STIM210_PARAMETERS_temperature_range_high_degC = 50.0f;
+const float STIM210_PARAMETERS_temperature_range_low_degC = -50.0f;
+// The following parameters should be tuned with temperature experiment results
+const float STIM210_PARAMETERS_bias_coeff_compo_x[STIM210_PARAMETERS_kNumCoeffTempCalib] = { -1.698E-04f, 1.309E-06f };
+const float STIM210_PARAMETERS_scale_factor_coeff_compo_x[STIM210_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+const float STIM210_PARAMETERS_bias_coeff_compo_y[STIM210_PARAMETERS_kNumCoeffTempCalib] = { 2.990E-04, -6.060E-07f };
+const float STIM210_PARAMETERS_scale_factor_coeff_compo_y[STIM210_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+const float STIM210_PARAMETERS_bias_coeff_compo_z[STIM210_PARAMETERS_kNumCoeffTempCalib] = { -2.306E-04f, -6.303E-07f };
+const float STIM210_PARAMETERS_scale_factor_coeff_compo_z[STIM210_PARAMETERS_kNumCoeffTempCalib] = { 1.0f, 0.0f};
+
+// Gyro filter
+// 1st order Low Pass Filter
+const float STIM210_PARAMETERS_gyro_cut_off_freq_lpf_1st_Hz[PHYSICAL_CONST_THREE_DIM] = { 1.0f, 1.0f, 1.0f };
+// Spike filter
+const uint8_t STIM210_PARAMETERS_gyro_spike_count_limit_to_accept[PHYSICAL_CONST_THREE_DIM] = { 3, 3, 3 };
+const uint8_t STIM210_PARAMETERS_gyro_spike_count_limit_to_reject_continued_warning[PHYSICAL_CONST_THREE_DIM] = { 60, 60, 60 };
+const float STIM210_PARAMETERS_gyro_spike_reject_threshold_rad_s[PHYSICAL_CONST_THREE_DIM] = { 0.01f, 0.01f, 0.01f };
+const float STIM210_PARAMETERS_gyro_spike_amplitude_limit_to_accept_as_step_rad_s[PHYSICAL_CONST_THREE_DIM] = { 0.002f, 0.002f, 0.002f };
diff --git a/Examples/src_aobc_example/Settings/SatelliteParameters/structure_parameters.c b/Examples/src_aobc_example/Settings/SatelliteParameters/structure_parameters.c
new file mode 100644
index 00000000..3f6d3896
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/SatelliteParameters/structure_parameters.c
@@ -0,0 +1,14 @@
+/**
+ * @file structure_parameters.c
+ * @brief 衛星構造に関する衛星固有パラメータを管理する
+ */
+
+#include
+
+const float STRUCTURE_PARAMETERS_mass_sc_kg = 10.0;
+
+const float STRUCTURE_PARAMETERS_rmm_sc_body_Am2[PHYSICAL_CONST_THREE_DIM] = {0.3f, 0.2f, 0.1f};
+
+const float STRUCTURE_PARAMETERS_inertia_tensor_sc_body_kgm2[PHYSICAL_CONST_THREE_DIM][PHYSICAL_CONST_THREE_DIM] = {{0.1f, 0.0f, 0.0f},
+ {0.0f, 0.2f, 0.0f},
+ {0.0f, 0.0f, 0.3f}};
diff --git a/Examples/src_aobc_example/Settings/user_defined_i2c_address.h b/Examples/src_aobc_example/Settings/user_defined_i2c_address.h
new file mode 100644
index 00000000..d478f5aa
--- /dev/null
+++ b/Examples/src_aobc_example/Settings/user_defined_i2c_address.h
@@ -0,0 +1,32 @@
+#ifndef USER_DEFINED_I2C_ADDRESS_H_
+#define USER_DEFINED_I2C_ADDRESS_H_
+
+// Undefined
+#undef I2C_DEVICE_ADDR_AOBC_MPU
+#undef I2C_DEVICE_ADDR_AOBC_MPU_AK
+#undef I2C_DEVICE_ADDR_AOBC_RM
+#undef I2C_DEVICE_ADDR_EXT_RM
+#undef I2C_DEVICE_ADDR_SS_PY
+#undef I2C_DEVICE_ADDR_SS_MY
+#undef I2C_DEVICE_ADDR_SS_PZ
+#undef I2C_DEVICE_ADDR_SS_MZ
+#undef I2C_DEVICE_ADDR_RW_X
+#undef I2C_DEVICE_ADDR_RW_Y
+#undef I2C_DEVICE_ADDR_RW_Z
+
+// Sensors
+#define I2C_DEVICE_ADDR_AOBC_MPU (0x68) //!< MPU9250 on AOBC board
+#define I2C_DEVICE_ADDR_AOBC_MPU_AK (0x0c) //!< AK8963 magnetometer in MPU9250
+#define I2C_DEVICE_ADDR_AOBC_RM (0x20) //!< RM3100 magnetometer on AOBC board
+#define I2C_DEVICE_ADDR_EXT_RM (0x23) //!< External RM3100 magnetometer
+#define I2C_DEVICE_ADDR_SS_PY (0x70) //!< nanoSSOC-D60 Sun-sensor on PY
+#define I2C_DEVICE_ADDR_SS_MY (0x71) //!< nanoSSOC-D60 Sun-sensor on MY
+#define I2C_DEVICE_ADDR_SS_PZ (0x72) //!< nanoSSOC-D60 Sun-sensor on PZ
+#define I2C_DEVICE_ADDR_SS_MZ (0x7C) //!< nanoSSOC-D60 Sun-sensor on MZ
+
+// RWs
+#define I2C_DEVICE_ADDR_RW_X (0x11) //!< RW on X-axis
+#define I2C_DEVICE_ADDR_RW_Y (0x37) //!< RW on Y-axis
+#define I2C_DEVICE_ADDR_RW_Z (0x39) //!< RW on Z-axis
+
+#endif // USER_DEFINED_I2C_ADDRESS_H_
diff --git a/src/src_user/Applications/DriverInstances/DI_i2c_example.c b/src/src_user/Applications/DriverInstances/DI_i2c_example.c
index 942d0cd9..dd387928 100644
--- a/src/src_user/Applications/DriverInstances/DI_i2c_example.c
+++ b/src/src_user/Applications/DriverInstances/DI_i2c_example.c
@@ -5,7 +5,7 @@
// user side
#include "DI_i2c_example.h"
-#include "../../Settings/port_config.h"
+#include
static I2C_Config I2C_EXAMPLE_port_;
diff --git a/src/src_user/Applications/DriverInstances/di_fm25v10.c b/src/src_user/Applications/DriverInstances/di_fm25v10.c
index 275bd395..2d07dae7 100644
--- a/src/src_user/Applications/DriverInstances/di_fm25v10.c
+++ b/src/src_user/Applications/DriverInstances/di_fm25v10.c
@@ -9,8 +9,8 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
+#include
+#include
#include
static void DI_FM25V10_init_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_fm25v10.h b/src/src_user/Applications/DriverInstances/di_fm25v10.h
index e616382f..0e717265 100644
--- a/src/src_user/Applications/DriverInstances/di_fm25v10.h
+++ b/src/src_user/Applications/DriverInstances/di_fm25v10.h
@@ -5,7 +5,7 @@
#ifndef DI_FM25V10_H_
#define DI_FM25V10_H_
-#include "../../Drivers/Cdh/fm25v10.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_ina260.c b/src/src_user/Applications/DriverInstances/di_ina260.c
index c23d21d4..ad0c08b6 100644
--- a/src/src_user/Applications/DriverInstances/di_ina260.c
+++ b/src/src_user/Applications/DriverInstances/di_ina260.c
@@ -10,9 +10,9 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
+#include
+#include
+#include
static void DI_INA260_init_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_ina260.h b/src/src_user/Applications/DriverInstances/di_ina260.h
index 3b8f0810..f8e08817 100644
--- a/src/src_user/Applications/DriverInstances/di_ina260.h
+++ b/src/src_user/Applications/DriverInstances/di_ina260.h
@@ -5,7 +5,7 @@
#ifndef DI_INA260_H_
#define DI_INA260_H_
-#include "../../Drivers/Power/ina260.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_mobc.c b/src/src_user/Applications/DriverInstances/di_mobc.c
index 498d8781..7d0f4391 100644
--- a/src/src_user/Applications/DriverInstances/di_mobc.c
+++ b/src/src_user/Applications/DriverInstances/di_mobc.c
@@ -7,8 +7,8 @@
#include "di_mobc.h"
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
+#include
+#include
static void DI_MOBC_init_(void);
static void DI_MOBC_update_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_mobc.h b/src/src_user/Applications/DriverInstances/di_mobc.h
index 7899fe6a..72f84379 100644
--- a/src/src_user/Applications/DriverInstances/di_mobc.h
+++ b/src/src_user/Applications/DriverInstances/di_mobc.h
@@ -5,7 +5,7 @@
#ifndef DI_MOBC_H_
#define DI_MOBC_H_
-#include "../../Drivers/Etc/mobc.h"
+#include
#include
#include
diff --git a/src/src_user/Applications/DriverInstances/di_mpu9250.c b/src/src_user/Applications/DriverInstances/di_mpu9250.c
index 4d22644b..be343d2e 100644
--- a/src/src_user/Applications/DriverInstances/di_mpu9250.c
+++ b/src/src_user/Applications/DriverInstances/di_mpu9250.c
@@ -9,10 +9,13 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../../Library/matrix33.h"
+#include
+#include
+#include
+#include
+
+// Satellite Parameters
+#include
static void DI_MPU9250_init_(void);
static void DI_MPU9250_update_(void);
@@ -30,8 +33,6 @@ static DS_StreamRecBuffer DI_AK8963_rx_buffer_;
static uint8_t DI_MPU9250_rx_buffer_allocation_[DS_STREAM_REC_BUFFER_SIZE_DEFAULT];
static uint8_t DI_AK8963_rx_buffer_allocation_[DS_STREAM_REC_BUFFER_SIZE_DEFAULT];
-static const uint8_t DI_MPU9250_kNumCoeffTempCalib_ = 2;
-
static uint8_t DI_MPU9250_is_initialized_[MPU9250_IDX_MAX] = { 0 }; //!< 0 = not initialized, 1 = initialized
@@ -93,54 +94,50 @@ static void DI_MPU9250_init_(void)
Printf("MPU9250: ang_vel_bias set error.\n");
}
- float mag_bias_compo_nT[PHYSICAL_CONST_THREE_DIM] = { -18417.53f, -30423.31f, 20969.18f }; // 実機計測値
- ret_math = MPU9250_set_mag_bias_compo_nT(&mpu9250_driver_[MPU9250_IDX_ON_AOBC], mag_bias_compo_nT);
+ ret_math = MPU9250_set_mag_bias_compo_nT(&mpu9250_driver_[MPU9250_IDX_ON_AOBC], MPU9250_PARAMETERS_mag_bias_compo_nT);
if (ret_math != C2A_MATH_ERROR_OK)
{
Printf("MPU9250: mag_bias set error.\n");
}
// 温度補正
- const float kRangeLow = -50.0f; // degC
- const float kRangeHigh = 50.0f; // degC
- float bias_coeff[DI_MPU9250_kNumCoeffTempCalib_];
- float scale_factor_coeff[DI_MPU9250_kNumCoeffTempCalib_];
+ const float kRangeLow = MPU9250_PARAMETERS_temperature_range_low_degC;
+ const float kRangeHigh = MPU9250_PARAMETERS_temperature_range_high_degC;
// 切片は実機計測値、切片はOPT-1, RWASATでの測定値を利用
// 特にSFは小さいのでなしとする
// SF,バイアスは y = SF*x - BIASという式を想定
// X軸
- bias_coeff[0] = -0.024f;
- bias_coeff[1] = 0.0002f;
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_bias_compo_rad_s[0]),
- DI_MPU9250_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_bias_coeff_compo_x,
+ kRangeLow, kRangeHigh);
if (ret3 < 0) Printf("MPU9250 Gyro-X Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
+
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_scale_factor_compo[0]),
- DI_MPU9250_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
- if (ret3 < 0) Printf("MPU9250 Gyro-X SF Temperature Caliblation init Failed ! \n");
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_scale_factor_coeff_compo_x,
+ kRangeLow, kRangeHigh);
+ if (ret3 < 0) Printf("MPU9250 Gyro-X SF Temperature Calibration init Failed ! \n");
+
// Y軸
- bias_coeff[0] = 0.0058f;
- bias_coeff[1] = -0.0005f;
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_bias_compo_rad_s[1]),
- DI_MPU9250_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
- if (ret3 < 0) Printf("MPU9250 Gyro-Y Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_bias_coeff_compo_y,
+ kRangeLow, kRangeHigh);
+ if (ret3 < 0) Printf("MPU9250 Gyro-Y Bias Temperature Calibration init Failed ! \n");
+
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_scale_factor_compo[1]),
- DI_MPU9250_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
- if (ret3 < 0) Printf("MPU9250 Gyro-Y SF Temperature Caliblation init Failed ! \n");
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_scale_factor_coeff_compo_x,
+ kRangeLow, kRangeHigh);
+ if (ret3 < 0) Printf("MPU9250 Gyro-Y SF Temperature Calibration init Failed ! \n");
+
// Z軸
- bias_coeff[0] = 0.0179f;
- bias_coeff[1] = 0.0001f;
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_bias_compo_rad_s[2]),
- DI_MPU9250_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
- if (ret3 < 0) Printf("MPU9250 Gyro-Z Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_bias_coeff_compo_z,
+ kRangeLow, kRangeHigh);
+ if (ret3 < 0) Printf("MPU9250 Gyro-Z Bias Temperature Calibration init Failed ! \n");
+
ret3 = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_scale_factor_compo[2]),
- DI_MPU9250_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
- if (ret3 < 0) Printf("MPU9250 Gyro-Z SF Temperature Caliblation init Failed ! \n");
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, MPU9250_PARAMETERS_scale_factor_coeff_compo_x,
+ kRangeLow, kRangeHigh);
+ if (ret3 < 0) Printf("MPU9250 Gyro-Z SF Temperature Calibration init Failed ! \n");
return;
}
@@ -320,14 +317,14 @@ CCP_CmdRet Cmd_DI_MPU9250_SET_ANG_VEL_BIAS_TEMP_CALIB(const CommonCmdPacket* pac
ENDIAN_memcpy(&range_high_degC, param + offset, sizeof(float));
offset += sizeof(float);
- float coeff[DI_MPU9250_kNumCoeffTempCalib_];
+ float coeff[MPU9250_PARAMETERS_kNumCoeffTempCalib];
ENDIAN_memcpy(&coeff[0], param + offset, sizeof(float));
offset += sizeof(float);
ENDIAN_memcpy(&coeff[1], param + offset, sizeof(float));
offset += sizeof(float);
int ret = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_bias_compo_rad_s[axis]),
- DI_MPU9250_kNumCoeffTempCalib_, coeff, range_low_degC, range_high_degC);
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, coeff, range_low_degC, range_high_degC);
if (ret < 0) return CCP_make_cmd_ret_without_err_code(CCP_EXEC_ILLEGAL_CONTEXT);
return CCP_make_cmd_ret_without_err_code(CCP_EXEC_SUCCESS);
@@ -350,14 +347,14 @@ CCP_CmdRet Cmd_DI_MPU9250_SET_ANG_VEL_SF_TEMP_CALIB(const CommonCmdPacket* packe
ENDIAN_memcpy(&range_high_degC, param + offset, sizeof(float));
offset += sizeof(float);
- float coeff[DI_MPU9250_kNumCoeffTempCalib_];
+ float coeff[MPU9250_PARAMETERS_kNumCoeffTempCalib];
ENDIAN_memcpy(&coeff[0], param + offset, sizeof(float));
offset += sizeof(float);
ENDIAN_memcpy(&coeff[1], param + offset, sizeof(float));
offset += sizeof(float);
int ret = POLYNOMIAL_APPROX_initialize(&(di_mpu9250_[MPU9250_IDX_ON_AOBC].gyro_scale_factor_compo[axis]),
- DI_MPU9250_kNumCoeffTempCalib_, coeff, range_low_degC, range_high_degC);
+ MPU9250_PARAMETERS_kNumCoeffTempCalib, coeff, range_low_degC, range_high_degC);
if (ret < 0) return CCP_make_cmd_ret_without_err_code(CCP_EXEC_ILLEGAL_CONTEXT);
return CCP_make_cmd_ret_without_err_code(CCP_EXEC_SUCCESS);
diff --git a/src/src_user/Applications/DriverInstances/di_mpu9250.h b/src/src_user/Applications/DriverInstances/di_mpu9250.h
index 74a8e02b..83ab3bfb 100644
--- a/src/src_user/Applications/DriverInstances/di_mpu9250.h
+++ b/src/src_user/Applications/DriverInstances/di_mpu9250.h
@@ -5,9 +5,9 @@
#ifndef DI_MPU9250_H_
#define DI_MPU9250_H_
-#include "../../Drivers/Aocs/mpu9250.h"
+#include
#include
-#include "../../Library/SignalProcess/polynomial_approximation.h"
+#include
/**
* @enum MPU9250_IDX
diff --git a/src/src_user/Applications/DriverInstances/di_mtq_seiren.c b/src/src_user/Applications/DriverInstances/di_mtq_seiren.c
index 324e9cd9..0af5c8b2 100644
--- a/src/src_user/Applications/DriverInstances/di_mtq_seiren.c
+++ b/src/src_user/Applications/DriverInstances/di_mtq_seiren.c
@@ -9,9 +9,9 @@
#include
#include
#include
-#include "../UserDefined/AOCS/aocs_manager.h"
-#include "../../Settings/port_config.h"
-#include "../../Library/vector3.h"
+#include
+#include
+#include
static MTQ_SEIREN_Driver mtq_seiren_driver_[MTQ_SEIREN_IDX_MAX];
diff --git a/src/src_user/Applications/DriverInstances/di_mtq_seiren.h b/src/src_user/Applications/DriverInstances/di_mtq_seiren.h
index ed82b0b6..3009c859 100644
--- a/src/src_user/Applications/DriverInstances/di_mtq_seiren.h
+++ b/src/src_user/Applications/DriverInstances/di_mtq_seiren.h
@@ -5,8 +5,8 @@
#ifndef DI_MTQ_SEIREN_H_
#define DI_MTQ_SEIREN_H_
-#include "../../Drivers/Aocs/mtq_seiren.h"
-#include "../UserDefined/AOCS/aocs_error.h"
+#include
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_nanossoc_d60.c b/src/src_user/Applications/DriverInstances/di_nanossoc_d60.c
index 00b10649..a34f56c9 100644
--- a/src/src_user/Applications/DriverInstances/di_nanossoc_d60.c
+++ b/src/src_user/Applications/DriverInstances/di_nanossoc_d60.c
@@ -9,10 +9,13 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../../IfWrapper/GPIO.h"
+#include
+#include
+#include
+#include
+
+// Satellite Parameters
+#include
static void DI_NANOSSOC_D60_init_(void);
static void DI_NANOSSOC_D60_update_(void);
@@ -69,41 +72,25 @@ static void DI_NANOSSOC_D60_init_(void)
}
C2A_MATH_ERROR ret_math;
- Quaternion q_py_c2b;
- q_py_c2b = QUATERNION_make_x_rot(PHYSICAL_CONST_degree_to_radian(90.0f));
- ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_PY], q_py_c2b);
+ ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_PY], NANOSSOC_D60_PARAMETERS_py_quaternion_c2b);
if (ret_math != C2A_MATH_ERROR_OK)
{
Printf("NanoSSOC-D60: q_py_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
- Quaternion q_my_c2b;
- QUATERNION_make_from_euler_angles(&q_my_c2b,
- PHYSICAL_CONST_degree_to_radian(90.0f),
- PHYSICAL_CONST_degree_to_radian(0.0f),
- PHYSICAL_CONST_degree_to_radian(180.0f),
- EULER_ANGLE_ROTATION_ORDER_123);
- ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_MY], q_my_c2b);
+ ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_MY], NANOSSOC_D60_PARAMETERS_my_quaternion_c2b);
if (ret_math != C2A_MATH_ERROR_OK)
{
Printf("NanoSSOC-D60: q_py_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
- Quaternion q_pz_c2b;
- q_pz_c2b = QUATERNION_make_z_rot(PHYSICAL_CONST_degree_to_radian(90.0f));
- ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_PZ], q_pz_c2b);
+ ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_PZ], NANOSSOC_D60_PARAMETERS_pz_quaternion_c2b);
if (ret_math != C2A_MATH_ERROR_OK)
{
Printf("NanoSSOC-D60: q_py_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
- Quaternion q_mz_c2b;
- QUATERNION_make_from_euler_angles(&q_mz_c2b,
- PHYSICAL_CONST_degree_to_radian(-90.0f),
- PHYSICAL_CONST_degree_to_radian(0.0f),
- PHYSICAL_CONST_degree_to_radian(180.0f),
- EULER_ANGLE_ROTATION_ORDER_321);
- ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_MZ], q_mz_c2b);
+ ret_math = NANOSSOC_D60_set_frame_transform_c2b(&nanossoc_d60_driver_[NANOSSOC_D60_IDX_ON_MZ], NANOSSOC_D60_PARAMETERS_mz_quaternion_c2b);
if (ret_math != C2A_MATH_ERROR_OK)
{
Printf("NanoSSOC-D60: q_py_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
diff --git a/src/src_user/Applications/DriverInstances/di_nanossoc_d60.h b/src/src_user/Applications/DriverInstances/di_nanossoc_d60.h
index 290e0718..e9f25c34 100644
--- a/src/src_user/Applications/DriverInstances/di_nanossoc_d60.h
+++ b/src/src_user/Applications/DriverInstances/di_nanossoc_d60.h
@@ -5,7 +5,7 @@
#ifndef DI_NANOSSOC_D60_H_
#define DI_NANOSSOC_D60_H_
-#include "../../Drivers/Aocs/nanossoc_d60.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_oem7600.c b/src/src_user/Applications/DriverInstances/di_oem7600.c
index 8ad85cf6..f97ffc47 100644
--- a/src/src_user/Applications/DriverInstances/di_oem7600.c
+++ b/src/src_user/Applications/DriverInstances/di_oem7600.c
@@ -8,10 +8,10 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../UserDefined/AOCS/aocs_manager.h"
+#include
+#include
+#include
+#include
static void DI_OEM7600_init_(void);
static void DI_OEM7600_update_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_oem7600.h b/src/src_user/Applications/DriverInstances/di_oem7600.h
index e43dc40c..308c1e68 100644
--- a/src/src_user/Applications/DriverInstances/di_oem7600.h
+++ b/src/src_user/Applications/DriverInstances/di_oem7600.h
@@ -5,7 +5,7 @@
#ifndef DI_OEM7600_H_
#define DI_OEM7600_H_
-#include "../../Drivers/Aocs/oem7600.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_rm3100.c b/src/src_user/Applications/DriverInstances/di_rm3100.c
index 68ea287b..6ac50124 100644
--- a/src/src_user/Applications/DriverInstances/di_rm3100.c
+++ b/src/src_user/Applications/DriverInstances/di_rm3100.c
@@ -10,10 +10,13 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../../Library/vector3.h"
+#include
+#include
+#include
+#include
+
+// Satellite Parameters
+#include "../../Settings/SatelliteParameters/rm3100_parameters.h"
static void DI_RM3100_init_(void);
static void DI_RM3100_update_(void);
@@ -27,8 +30,8 @@ static uint8_t DI_RM3100_rx_buffer_allocation_[RM3100_IDX_MAX][DS_STREAM_REC_BUF
static uint8_t DI_RM3100_is_initialized_[RM3100_IDX_MAX] = { 0, 0 }; //!< 0 = not initialized, 1 = initialized
-static float DI_RM3100_default_bias_aobc_compo_nT_[PHYSICAL_CONST_THREE_DIM] = { 32808.59f, -79748.68f, 22059.96f }; //!< デフォルトバイアス値
-static float DI_RM3100_default_bias_ext_compo_nT_[PHYSICAL_CONST_THREE_DIM] = { 36824.97f, -4596.48f, -1133.40f }; //!< デフォルトバイアス値
+static float DI_RM3100_default_bias_aobc_compo_nT_[PHYSICAL_CONST_THREE_DIM];
+static float DI_RM3100_default_bias_ext_compo_nT_[PHYSICAL_CONST_THREE_DIM];
static float DI_RM3100_kBiasDiffMax_nT_ = 20000.0f; //!< 磁気バイアスAddコマンドでトータルバイアスがデフォルト値から離れすぎないようにするためのしきい値
@@ -73,6 +76,7 @@ static void DI_RM3100_init_(void)
Printf("RM3100: q_aobc_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
+ VECTOR3_copy(DI_RM3100_default_bias_aobc_compo_nT_, RM3100_PARAMETERS_mag_aobc_bias_compo_nT);
ret = RM3100_set_mag_bias_compo_nT(&rm3100_driver_[RM3100_IDX_ON_AOBC], DI_RM3100_default_bias_aobc_compo_nT_);
if (ret != C2A_MATH_ERROR_OK)
{
@@ -84,18 +88,13 @@ static void DI_RM3100_init_(void)
PORT_CH_I2C_SENSORS,
I2C_DEVICE_ADDR_EXT_RM,
&DI_RM3100_rx_buffer_[RM3100_IDX_EXTERNAL]);
- Quaternion q_ext_c2b;
- QUATERNION_make_from_euler_angles(&q_ext_c2b,
- PHYSICAL_CONST_degree_to_radian(-90.0f),
- PHYSICAL_CONST_degree_to_radian(0.0f),
- PHYSICAL_CONST_degree_to_radian(180.0f),
- EULER_ANGLE_ROTATION_ORDER_321);
- ret = RM3100_set_frame_transform_c2b(&rm3100_driver_[RM3100_IDX_EXTERNAL], q_ext_c2b);
+ ret = RM3100_set_frame_transform_c2b(&rm3100_driver_[RM3100_IDX_EXTERNAL], RM3100_PARAMETERS_mag_ext_quaternion_c2b);
if (ret != C2A_MATH_ERROR_OK)
{
Printf("RM3100: q_ext_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
+ VECTOR3_copy(DI_RM3100_default_bias_ext_compo_nT_, RM3100_PARAMETERS_mag_ext_bias_compo_nT);
ret = RM3100_set_mag_bias_compo_nT(&rm3100_driver_[RM3100_IDX_EXTERNAL], DI_RM3100_default_bias_ext_compo_nT_);
if (ret != C2A_MATH_ERROR_OK)
{
diff --git a/src/src_user/Applications/DriverInstances/di_rm3100.h b/src/src_user/Applications/DriverInstances/di_rm3100.h
index f8fa86a5..bbc5d8eb 100644
--- a/src/src_user/Applications/DriverInstances/di_rm3100.h
+++ b/src/src_user/Applications/DriverInstances/di_rm3100.h
@@ -5,7 +5,7 @@
#ifndef DI_RM3100_H_
#define DI_RM3100_H_
-#include "../../Drivers/Aocs/rm3100.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_rw0003.c b/src/src_user/Applications/DriverInstances/di_rw0003.c
index c84c4487..69359b36 100644
--- a/src/src_user/Applications/DriverInstances/di_rw0003.c
+++ b/src/src_user/Applications/DriverInstances/di_rw0003.c
@@ -11,11 +11,11 @@
#include
#include
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/AOCS/aocs_manager.h"
-#include "../../Library/vector3.h"
+#include
+#include
+#include
+#include
+#include
static void DI_RW0003_init_(void);
static void DI_RW0003_update_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_rw0003.h b/src/src_user/Applications/DriverInstances/di_rw0003.h
index 0a2267f8..8d45fb4b 100644
--- a/src/src_user/Applications/DriverInstances/di_rw0003.h
+++ b/src/src_user/Applications/DriverInstances/di_rw0003.h
@@ -5,8 +5,8 @@
#ifndef DI_RW0003_H_
#define DI_RW0003_H_
-#include "../../Drivers/Aocs/rw0003.h"
-#include "../UserDefined/AOCS/aocs_error.h"
+#include
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_sagitta.c b/src/src_user/Applications/DriverInstances/di_sagitta.c
index 78b6d522..77d60e00 100644
--- a/src/src_user/Applications/DriverInstances/di_sagitta.c
+++ b/src/src_user/Applications/DriverInstances/di_sagitta.c
@@ -11,9 +11,9 @@
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
+#include
+#include
+#include
static void DI_SAGITTA_init_(void);
static void DI_SAGITTA_update_(void);
diff --git a/src/src_user/Applications/DriverInstances/di_sagitta.h b/src/src_user/Applications/DriverInstances/di_sagitta.h
index 83c8e529..37c97a21 100644
--- a/src/src_user/Applications/DriverInstances/di_sagitta.h
+++ b/src/src_user/Applications/DriverInstances/di_sagitta.h
@@ -5,7 +5,7 @@
#ifndef DI_SAGITTA_H_
#define DI_SAGITTA_H_
-#include "../../Drivers/Aocs/sagitta.h"
+#include
#include
/**
diff --git a/src/src_user/Applications/DriverInstances/di_stim210.c b/src/src_user/Applications/DriverInstances/di_stim210.c
index 7173b923..2ddc57d6 100644
--- a/src/src_user/Applications/DriverInstances/di_stim210.c
+++ b/src/src_user/Applications/DriverInstances/di_stim210.c
@@ -9,10 +9,13 @@
#include
#include
#include
-#include "../../Settings/port_config.h"
-#include "../../Settings/DriverSuper/driver_buffer_define.h"
-#include "../UserDefined/Power/power_switch_control.h"
-#include "../../Library/matrix33.h"
+#include
+#include
+#include
+#include
+
+// Satellite Parameters
+#include
static void DI_STIM210_init_(void);
static void DI_STIM210_update_(void);
@@ -29,9 +32,6 @@ const DiStim210* const di_stim210 [STIM210_IDX_MAX] = {&di_stim210_[STIM210_IDX
static DS_StreamRecBuffer DI_STIM210_rx_buffer_;
static uint8_t DI_STIM210_rx_buffer_allocation_[DS_STREAM_REC_BUFFER_SIZE_DEFAULT];
-static const uint8_t DI_STIM210_kNumCoeffTempCalib_ = 2;
-
-
AppInfo DI_STIM210_update(void)
{
return AI_create_app_info("update_DI_STIM210", DI_STIM210_init_, DI_STIM210_update_);
@@ -74,55 +74,34 @@ static void DI_STIM210_init_(void)
Printf("STIM210: q_c2b set error.\n"); // 初期化時のエラーはデバッグ表示して知らせるだけ
}
- float ang_vel_bias_compo_rad_s[PHYSICAL_CONST_THREE_DIM] = { -2.27E-04f, 2.80E-04f, -3.37E-04f }; // TODO_L: 温度補正されるので、削除しても良い
- ret_math = STIM210_set_ang_vel_bias_compo_rad_s(&stim210_driver_[STIM210_IDX_IN_UNIT], ang_vel_bias_compo_rad_s);
- if (ret_math != C2A_MATH_ERROR_OK)
- {
- Printf("STIM210: ang_vel_bias set error.\n");
- }
-
// 温度補正
- const float kRangeLow = -50.0f; // degC
- const float kRangeHigh = 50.0f; // degC
- float bias_coeff[DI_STIM210_kNumCoeffTempCalib_];
- float scale_factor_coeff[DI_STIM210_kNumCoeffTempCalib_];
+ const float kRangeLow = STIM210_PARAMETERS_temperature_range_low_degC;
+ const float kRangeHigh = STIM210_PARAMETERS_temperature_range_high_degC;
// 計測値から設定するが温度依存性はかなり小さい
// 特にSFは取付誤差と見分けづらいのでなしとする
// SF,バイアスは y = SF*x - BIASという式を想定
// X軸
- bias_coeff[0] = -1.698E-04f;
- bias_coeff[1] = 1.309E-06f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].bias_compo_rad_s[0]),
- DI_STIM210_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_bias_coeff_compo_x, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-X Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].scale_factor_compo[0]),
- DI_STIM210_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_scale_factor_coeff_compo_x, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-X SF Temperature Caliblation init Failed ! \n");
// Y軸
- bias_coeff[0] = 2.990E-04f;
- bias_coeff[1] = -6.060E-07f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].bias_compo_rad_s[1]),
- DI_STIM210_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_bias_coeff_compo_y, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-Y Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].scale_factor_compo[1]),
- DI_STIM210_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_scale_factor_coeff_compo_y, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-Y SF Temperature Caliblation init Failed ! \n");
// Z軸
- bias_coeff[0] = -2.306E-04f;
- bias_coeff[1] = -6.303E-07f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].bias_compo_rad_s[2]),
- DI_STIM210_kNumCoeffTempCalib_, bias_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_bias_coeff_compo_z, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-Z Bias Temperature Caliblation init Failed ! \n");
- scale_factor_coeff[0] = 1.0f;
- scale_factor_coeff[1] = 0.0f;
ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].scale_factor_compo[2]),
- DI_STIM210_kNumCoeffTempCalib_, scale_factor_coeff, kRangeLow, kRangeHigh);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, STIM210_PARAMETERS_scale_factor_coeff_compo_z, kRangeLow, kRangeHigh);
if (ret < 0) Printf("STIM210 Gyro-Z SF Temperature Caliblation init Failed ! \n");
return;
@@ -366,15 +345,15 @@ CCP_CmdRet Cmd_DI_STIM210_SET_ANG_VEL_BIAS_TEMP_CALIB(const CommonCmdPacket* pac
ENDIAN_memcpy(&range_high_degC, param + offset, sizeof(float));
offset += sizeof(float);
- float coeff[DI_STIM210_kNumCoeffTempCalib_];
- for (uint8_t coeff_idx = 0; coeff_idx < DI_STIM210_kNumCoeffTempCalib_; coeff_idx++)
+ float coeff[STIM210_PARAMETERS_kNumCoeffTempCalib];
+ for (uint8_t coeff_idx = 0; coeff_idx < STIM210_PARAMETERS_kNumCoeffTempCalib; coeff_idx++)
{
ENDIAN_memcpy(&coeff[coeff_idx], param + offset, sizeof(float));
offset += sizeof(float);
}
int ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].bias_compo_rad_s[axis]),
- DI_STIM210_kNumCoeffTempCalib_, coeff, range_low_degC, range_high_degC);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, coeff, range_low_degC, range_high_degC);
if (ret < 0) return CCP_make_cmd_ret_without_err_code(CCP_EXEC_ILLEGAL_CONTEXT);
return CCP_make_cmd_ret_without_err_code(CCP_EXEC_SUCCESS);
@@ -397,15 +376,15 @@ CCP_CmdRet Cmd_DI_STIM210_SET_ANG_VEL_SF_TEMP_CALIB(const CommonCmdPacket* packe
ENDIAN_memcpy(&range_high_degC, param + offset, sizeof(float));
offset += sizeof(float);
- float coeff[DI_STIM210_kNumCoeffTempCalib_];
- for (uint8_t coeff_idx = 0; coeff_idx < DI_STIM210_kNumCoeffTempCalib_; coeff_idx++)
+ float coeff[STIM210_PARAMETERS_kNumCoeffTempCalib];
+ for (uint8_t coeff_idx = 0; coeff_idx < STIM210_PARAMETERS_kNumCoeffTempCalib; coeff_idx++)
{
ENDIAN_memcpy(&coeff[coeff_idx], param + offset, sizeof(float));
offset += sizeof(float);
}
int ret = POLYNOMIAL_APPROX_initialize(&(di_stim210_[STIM210_IDX_IN_UNIT].scale_factor_compo[axis]),
- DI_STIM210_kNumCoeffTempCalib_, coeff, range_low_degC, range_high_degC);
+ STIM210_PARAMETERS_kNumCoeffTempCalib, coeff, range_low_degC, range_high_degC);
if (ret < 0) return CCP_make_cmd_ret_without_err_code(CCP_EXEC_ILLEGAL_CONTEXT);
return CCP_make_cmd_ret_without_err_code(CCP_EXEC_SUCCESS);
diff --git a/src/src_user/Applications/DriverInstances/di_stim210.h b/src/src_user/Applications/DriverInstances/di_stim210.h
index 9ddfdbe2..3d13f819 100644
--- a/src/src_user/Applications/DriverInstances/di_stim210.h
+++ b/src/src_user/Applications/DriverInstances/di_stim210.h
@@ -5,9 +5,9 @@
#ifndef DI_STIM210_H_
#define DI_STIM210_H_
-#include "../../Drivers/Aocs/stim210.h"
+#include
#include
-#include "../../Library/SignalProcess/polynomial_approximation.h"
+#include
/**
* @enum STIM210_IDX
diff --git a/src/src_user/Applications/DriverInstances/uart_example.c b/src/src_user/Applications/DriverInstances/uart_example.c
index 026001fd..1e9aad46 100644
--- a/src/src_user/Applications/DriverInstances/uart_example.c
+++ b/src/src_user/Applications/DriverInstances/uart_example.c
@@ -2,7 +2,7 @@
#include
#include
-#include "../../Settings/port_config.h"
+#include
static UART_Config uart_debug_;
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.c
index 75a71bc1..39744bda 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.c
@@ -7,11 +7,14 @@
#include "bdot.h"
#include
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/math_constants.h"
-#include "../aocs_manager.h"
-#include "../../../DriverInstances/di_mtq_seiren.h"
+#include
+#include
+#include
+#include
+#include
+
+// Satellite parameters
+#include
static Bdot bdot_;
const Bdot* const bdot = &bdot_;
@@ -71,9 +74,9 @@ AppInfo APP_BDOT_create_app(void)
static void APP_BDOT_init_(void)
{
- VECTOR3_initialize(bdot_.control_gain, -0.1f);
- bdot_.minimum_time_derivative_step_ms = 100; // SILS試験で正しくレートダンプに成功したときの値を設定している
- bdot_.mtq_output_time_length_ms = 1000; // SILS試験で正しくレートダンプに成功したときの値を設定している
+ VECTOR3_copy(bdot_.control_gain, ATTITUDE_CONTROL_PARAMETERS_bdot_control_gain);
+ bdot_.minimum_time_derivative_step_ms = ATTITUDE_CONTROL_PARAMETERS_bdot_minimum_time_derivative_step_ms;
+ bdot_.mtq_output_time_length_ms = ATTITUDE_CONTROL_PARAMETERS_bdot_mtq_output_time_length_ms;
bdot_.mtq_output_turned_on_obc_time = TMGR_get_master_clock();
bdot_.time_derivative_variables.previous_obc_time = TMGR_get_master_clock();
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.h
index 52b2b328..7a1f2c17 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/bdot.h
@@ -8,9 +8,9 @@
#include
#include
#include
-#include
-#include "../../../../Library/physical_constants.h"
-#include "../../AOCS/aocs_error.h"
+#include
+#include
+#include
/**
* @struct Bdot
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.c
index 1c675446..5d6a1893 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.c
@@ -11,18 +11,21 @@
#include
#include
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/math_constants.h"
-#include "../../../../Library/ControlUtility/gyroscopic_effect.h"
-#include "../HardwareDependent/ActuatorControllers/mtq_seiren_controller.h"
-#include "../../../../Library/ControlUtility/cross_product_control.h"
-#include "../aocs_manager.h"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
#include
#include
#include
+// Satellite Parameters
+#include
+
static SunPointing sun_pointing_;
const SunPointing* const sun_pointing = &sun_pointing_;
@@ -85,7 +88,7 @@ static void APP_SUN_POINTING_init_(void)
CROSS_PRODUCT_CONTROL_init(&sun_pointing_.cross_product_cntrl);
- sun_pointing_.sun_pointing_axis_id = SUN_POINTING_AXIS_ID_Z;
+ sun_pointing_.sun_pointing_axis_id = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_axis_id;
sun_pointing_.control_state = SUN_POINTING_CONTROL_STATE_TRANSIENT;
float sun_vec_target_body[PHYSICAL_CONST_THREE_DIM] = { 0.0f, 0.0f, 0.0f };
@@ -94,52 +97,35 @@ static void APP_SUN_POINTING_init_(void)
// ノミナルのスピン軸 (Z軸) 周りの姿勢制御はフリーとし,スピン軸周りはレートのみPD制御する
PidGains gains_att[PHYSICAL_CONST_THREE_DIM];
- gains_att[0].p_gain = 5.0e-5f;
- gains_att[1].p_gain = 10.0e-5f;
- gains_att[2].p_gain = 0.0f;
-
- gains_att[0].i_gain = 0.0f;
- gains_att[1].i_gain = 0.0f;
- gains_att[2].i_gain = 0.0f;
-
- gains_att[0].d_gain = 0.0f;
- gains_att[1].d_gain = 0.0f;
- gains_att[2].d_gain = 0.0f;
+ gains_att[0] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_x;
+ gains_att[1] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_y;
+ gains_att[2] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_gains_body_z;
PidGains gains_omega[PHYSICAL_CONST_THREE_DIM];
- gains_omega[0].p_gain = 1.0e-2f;
- gains_omega[1].p_gain = 2.0e-2f;
- gains_omega[2].p_gain = 7.0e-3f;
-
- gains_omega[0].i_gain = 0.0f;
- gains_omega[1].i_gain = 0.0f;
- gains_omega[2].i_gain = 0.0f;
-
- gains_omega[0].d_gain = 0.0f;
- gains_omega[1].d_gain = 0.0f;
- gains_omega[2].d_gain = 2.0e-2f;
-
- sun_pointing_.max_direct_feedback_angle_rad = PHYSICAL_CONST_degree_to_radian(20.0f);
- sun_pointing_.max_direct_feedback_rate_rad_s = 1.6e-3f;
- sun_pointing_.max_integral_angle_rad = PHYSICAL_CONST_degree_to_radian(20.0f);
- sun_pointing_.max_angle_to_run_integral_control_rad = PHYSICAL_CONST_degree_to_radian(30.0f);
- sun_pointing_.integral_control_permission_angle_rad = PHYSICAL_CONST_degree_to_radian(40.0f);
-
- sun_pointing_.acceptable_angle_error_to_spin_up_rad = PHYSICAL_CONST_degree_to_radian(30.0f);
- sun_pointing_.spin_rate_around_sun_rad_s = 1.4e-2f;
-
- sun_pointing_.lpf_sample_freq_Hz = 10.0f;
- sun_pointing_.lpf_trq_cutoff_freq_Hz = 0.10f;
- sun_pointing_.lpf_trq_damping_factor = 1.0f;
-
- sun_pointing_.lpf_trq_cutoff_freq_spin_axis_Hz = 0.03f;
- sun_pointing_.lpf_spin_rate_cutoff_freq_Hz = 5e-4f;
-
- // 下記の値はISS軌道を想定した値 (極軌道に近ければ緩めて良いはず)
- sun_pointing_.mtq_allowable_error_ratio_transient = 0.6f;
- sun_pointing_.correction_gain_transient = 0.0f;
- sun_pointing_.mtq_allowable_error_ratio_stable = 0.8f;
- sun_pointing_.correction_gain_stable = 0.25f;
+ gains_omega[0] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_x;
+ gains_omega[1] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_y;
+ gains_omega[2] = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_attitude_rate_gains_body_z;
+
+ sun_pointing_.max_direct_feedback_angle_rad = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_angle_rad;
+ sun_pointing_.max_direct_feedback_rate_rad_s = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_direct_feedback_rate_rad_s;
+ sun_pointing_.max_integral_angle_rad = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_integral_angle_rad;
+ sun_pointing_.max_angle_to_run_integral_control_rad = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_max_angle_to_run_integral_control_rad;
+ sun_pointing_.integral_control_permission_angle_rad = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_integral_control_permission_angle_rad;
+
+ sun_pointing_.acceptable_angle_error_to_spin_up_rad = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_acceptable_angle_error_to_spin_up_rad;
+ sun_pointing_.spin_rate_around_sun_rad_s = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_spin_rate_around_sun_rad_s;
+
+ sun_pointing_.lpf_sample_freq_Hz = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_sample_freq_Hz;
+ sun_pointing_.lpf_trq_cutoff_freq_Hz = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_Hz;
+ sun_pointing_.lpf_trq_damping_factor = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_damping_factor;
+
+ sun_pointing_.lpf_trq_cutoff_freq_spin_axis_Hz = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_trq_cutoff_freq_spin_axis_Hz;
+ sun_pointing_.lpf_spin_rate_cutoff_freq_Hz = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_lpf_spin_rate_cutoff_freq_Hz;
+
+ sun_pointing_.mtq_allowable_error_ratio_transient = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_transient;
+ sun_pointing_.correction_gain_transient = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_transient;
+ sun_pointing_.mtq_allowable_error_ratio_stable = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_mtq_allowable_error_ratio_stable;
+ sun_pointing_.correction_gain_stable = ATTITUDE_CONTROL_PARAMETERS_sun_pointing_correction_gain_stable;
for (uint8_t axis = 0; axis < PHYSICAL_CONST_THREE_DIM; axis++)
{
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.h
index 83183859..ac7b4c78 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/sun_pointing.h
@@ -8,11 +8,11 @@
#include
#include
#include
-#include "../../../../Library/physical_constants.h"
-#include "../../../../Library/ControlUtility/cross_product_control.h";
-#include "../../../../Library/pid_control.h"
-#include "../../../../Library/SignalProcess/z_filter.h"
-#include "../../AOCS/aocs_error.h"
+#include
+#include
+#include
+#include
+#include
/**
* @enum SUN_POINTING_AXIS_ID
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.c
index 59d02c1f..e1bb8b50 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.c
@@ -10,19 +10,22 @@
#include
#include
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/quaternion.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/math_constants.h"
-#include "../../../../Library/c2a_math.h"
-#include "../../../../Library/ControlUtility/gyroscopic_effect.h"
-#include "../HardwareDependent/ActuatorControllers/mtq_seiren_controller.h"
-#include "../aocs_manager.h"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
#include
#include
#include
+// Satellite Parameters
+#include
+
static ThreeAxisControlMtq three_axis_control_mtq_;
const ThreeAxisControlMtq* const three_axis_control_mtq = &three_axis_control_mtq_;
@@ -71,47 +74,29 @@ static void APP_TAC_MTQ_init_(void)
CROSS_PRODUCT_CONTROL_init(&three_axis_control_mtq_.cross_product_cntrl);
PidGains gains_att[PHYSICAL_CONST_THREE_DIM];
- gains_att[0].p_gain = 1.2e-4f;
- gains_att[1].p_gain = 2.0f * 1.2e-4f;
- gains_att[2].p_gain = 1.5f * 1.2e-4f;
-
- gains_att[0].i_gain = 0.0f;
- gains_att[1].i_gain = 0.0f;
- gains_att[2].i_gain = 0.0f;
-
- gains_att[0].d_gain = 0.0f;
- gains_att[1].d_gain = 0.0f;
- gains_att[2].d_gain = 0.0f;
+ gains_att[0] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_x;
+ gains_att[1] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_y;
+ gains_att[2] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_gains_body_z;
PidGains gains_omega[PHYSICAL_CONST_THREE_DIM];
- gains_omega[0].p_gain = 2.5e-2f;
- gains_omega[1].p_gain = 2.0f * 2.5e-2f;
- gains_omega[2].p_gain = 1.5f * 2.5e-2f;
-
- gains_omega[0].i_gain = 0.0f;
- gains_omega[1].i_gain = 0.0f;
- gains_omega[2].i_gain = 0.0f;
-
- gains_omega[0].d_gain = 0.0f;
- gains_omega[1].d_gain = 0.0f;
- gains_omega[2].d_gain = 0.0f;
-
- // 下記値の変更時は,HW側の出力最大値にかからない様に留意しながら,ゲインと組み合わせて調整すること.
- three_axis_control_mtq_.max_direct_feedback_angle_mtq_rad = PHYSICAL_CONST_degree_to_radian(18.0f);
- three_axis_control_mtq_.max_direct_feedback_rate_mtq_rad_s = 5.0e-3f;
- three_axis_control_mtq_.max_integral_angle_mtq_rad = PHYSICAL_CONST_degree_to_radian(40.0f);
- three_axis_control_mtq_.max_angle_to_run_integral_control_rad = PHYSICAL_CONST_degree_to_radian(30.0f);
-
- three_axis_control_mtq_.mtq_lpf_sample_freq_Hz = 10.0f;
- three_axis_control_mtq_.mtq_lpf_cutoff_freq_Hz = 0.30f;
- three_axis_control_mtq_.mtq_lpf_damping_factor = 1.0f;
-
- // 下記の値はISS軌道を想定した値 (極軌道に近ければ緩めて良いはず)
- three_axis_control_mtq_.allowable_error_ratio_transient = 0.6f;
- three_axis_control_mtq_.correction_gain_transient = 0.0f;
- three_axis_control_mtq_.allowable_error_ratio_stable = 0.60f;
- three_axis_control_mtq_.correction_gain_stable = 0.1f;
- three_axis_control_mtq_.acceptable_angle_error_as_stable_rad = PHYSICAL_CONST_degree_to_radian(20.0f);
+ gains_omega[0] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_x;
+ gains_omega[1] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_y;
+ gains_omega[2] = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_attitude_rate_gains_body_z;
+
+ three_axis_control_mtq_.max_direct_feedback_angle_mtq_rad = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_angle_rad;
+ three_axis_control_mtq_.max_direct_feedback_rate_mtq_rad_s = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_direct_feedback_rate_rad_s;
+ three_axis_control_mtq_.max_integral_angle_mtq_rad = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_integral_angle_rad;
+ three_axis_control_mtq_.max_angle_to_run_integral_control_rad = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_max_angle_to_run_integral_control_rad;
+
+ three_axis_control_mtq_.mtq_lpf_sample_freq_Hz = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_sample_freq_Hz;
+ three_axis_control_mtq_.mtq_lpf_cutoff_freq_Hz = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_cutoff_freq_Hz;
+ three_axis_control_mtq_.mtq_lpf_damping_factor = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_lpf_trq_damping_factor;
+
+ three_axis_control_mtq_.allowable_error_ratio_transient = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_transient;
+ three_axis_control_mtq_.correction_gain_transient = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_transient;
+ three_axis_control_mtq_.allowable_error_ratio_stable = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_mtq_allowable_error_ratio_stable;
+ three_axis_control_mtq_.correction_gain_stable = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_correction_gain_stable ;
+ three_axis_control_mtq_.acceptable_angle_error_as_stable_rad = ATTITUDE_CONTROL_PARAMETERS_tac_mtq_acceptable_angle_error_as_stable_rad;
for (uint8_t axis = 0; axis < PHYSICAL_CONST_THREE_DIM; axis++)
{
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.h
index 79787e3a..f2dc4bcf 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_mtq.h
@@ -9,11 +9,11 @@
#include
#include
#include
-#include "../../../../Library/physical_constants.h"
-#include "../../../../Library/ControlUtility/cross_product_control.h";
-#include "../../../../Library/pid_control.h"
-#include "../../../../Library/SignalProcess/z_filter.h"
-#include "../../AOCS/aocs_error.h"
+#include
+#include
+#include
+#include
+#include
/**
* @struct ThreeAxisControlMtq
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.c
index ee1e3108..e7604f08 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.c
@@ -10,16 +10,19 @@
#include
#include
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/quaternion.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/math_constants.h"
-#include "../../../../Library/ControlUtility/gyroscopic_effect.h"
-#include "../aocs_manager.h"
+#include
+#include
+#include
+#include
+#include
+#include
#include
#include
+// Satellite Parameters
+#include
+
static ThreeAxisControlRw three_axis_control_rw_;
const ThreeAxisControlRw* const three_axis_control_rw = &three_axis_control_rw_;
@@ -53,31 +56,15 @@ static void APP_TAC_RW_init_(void)
PID_CONTROL_init(&three_axis_control_rw_.pid_att[axis]);
}
- PidGains gains_omega[PHYSICAL_CONST_THREE_DIM];
- gains_omega[0].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 7.0e-1f;
- gains_omega[1].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 7.0e-1f;
- gains_omega[2].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 7.0e-1f;
-
- gains_omega[0].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 0.0e-1f;
- gains_omega[1].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 0.0e-1f;
- gains_omega[2].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 0.0e-1f;
-
- gains_omega[0].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 2.0e-2f;
- gains_omega[1].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 2.0e-2f;
- gains_omega[2].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 2.0e-2f;
-
PidGains gains_att[PHYSICAL_CONST_THREE_DIM];
- gains_att[0].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 1.0e-2f;
- gains_att[1].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 1.0e-2f;
- gains_att[2].p_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 1.0e-2f;
-
- gains_att[0].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 0.0e-2f;
- gains_att[1].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 0.0e-2f;
- gains_att[2].i_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 0.0e-2f;
+ gains_att[0] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_x;
+ gains_att[1] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_y;
+ gains_att[2] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_gains_body_z;
- gains_att[0].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[0][0] * 1.0e-2f;
- gains_att[1].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[1][1] * 1.0e-2f;
- gains_att[2].d_gain = aocs_manager->inertia_tensor_sc_body_kgm2[2][2] * 1.0e-2f;
+ PidGains gains_omega[PHYSICAL_CONST_THREE_DIM];
+ gains_omega[0] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_x;
+ gains_omega[1] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_y;
+ gains_omega[2] = ATTITUDE_CONTROL_PARAMETERS_tac_rw_attitude_rate_gains_body_z;
for (uint8_t axis = 0; axis < PHYSICAL_CONST_THREE_DIM; axis++)
{
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.h
index ff497365..25ceb5cd 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/three_axis_control_rw.h
@@ -9,9 +9,9 @@
#include
#include
#include
-#include "../../../../Library/physical_constants.h"
-#include "../../../../Library/pid_control.h"
-#include "../../AOCS/aocs_error.h"
+#include
+#include
+#include
/**
* @struct ThreeAxisControlRw
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.c
index c5d755bf..e1e03b96 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.c
@@ -10,8 +10,11 @@
#include
#include
-#include "../../../../Library/vector3.h"
-#include "../HardwareDependent/ActuatorControllers/mtq_seiren_controller.h"
+#include
+#include
+
+// Satellite Parameters
+#include
static Unloading unloading_;
const Unloading* const unloading = &unloading_;
@@ -43,13 +46,13 @@ AppInfo APP_UNLOADING_create_app(void)
static void APP_UNLOADING_init_(void)
{
- unloading_.angular_velocity_upper_threshold_rad_s = PHYSICAL_CONST_rpm_to_rad_sec(7000.0f);
- unloading_.angular_velocity_lower_threshold_rad_s = PHYSICAL_CONST_rpm_to_rad_sec(-7000.0f);
- unloading_.angular_velocity_target_rad_s = PHYSICAL_CONST_rpm_to_rad_sec(0.0f);
+ unloading_.angular_velocity_upper_threshold_rad_s = ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_upper_threshold_rad_s;
+ unloading_.angular_velocity_lower_threshold_rad_s = ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_lower_threshold_rad_s;
+ unloading_.angular_velocity_target_rad_s = ATTITUDE_CONTROL_PARAMETERS_unloading_angular_velocity_target_rad_s;
- unloading_.control_gain = -1.0e-7f;
+ unloading_.control_gain = ATTITUDE_CONTROL_PARAMETERS_unloading_control_gain;
- unloading_.exec_is_enable = APP_UNLOADING_EXEC_DISABLE;
+ unloading_.exec_is_enable = ATTITUDE_CONTROL_PARAMETERS_unloading_exec_is_enable;
for (int idx = 0; idx < AOCS_MANAGER_NUM_OF_RW; idx++)
{
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.h
index 9645086a..c4191f9c 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeControl/unloading.h
@@ -8,9 +8,9 @@
#include
#include
#include
-#include "../../../../Library/physical_constants.h"
-#include "../../../../Library/ControlUtility/cross_product_control.h"
-#include "../aocs_manager.h"
+#include
+#include
+#include
/**
* @enum APP_UNLOADING_STATE
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/fine_three_axis_determination.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/fine_three_axis_determination.c
index 1b69dbac..688e23f7 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/fine_three_axis_determination.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/fine_three_axis_determination.c
@@ -10,11 +10,14 @@
#include
#include
-#include "../aocs_manager.h"
-#include "../aocs_error.h"
-#include "../../../../Library/quaternion.h"
+#include
+#include
+#include
#include "stt_gyro_ekf.h"
+// Satellite parameters
+#include
+
static FineThreeAxisDetermination fine_three_axis_determination_;
const FineThreeAxisDetermination* const fine_three_axis_determination = &fine_three_axis_determination_;
@@ -35,7 +38,7 @@ AppInfo APP_FTAD_create_app(void)
static void APP_FTAD_init_(void)
{
fine_three_axis_determination_.previous_obc_time = TMGR_get_master_clock();
- fine_three_axis_determination_.method = APP_FTAD_METHOD_STT;
+ fine_three_axis_determination_.method = ATTITUDE_DETERMINATION_PARAMETERS_ftad_method;
}
static void APP_FTAD_exec_(void)
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/rough_three_axis_determination.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/rough_three_axis_determination.c
index a1fe6c6c..c94403db 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/rough_three_axis_determination.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/rough_three_axis_determination.c
@@ -10,13 +10,16 @@
#include
#include
-#include "../aocs_manager.h"
-#include "../aocs_error.h"
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/quaternion.h"
-#include "../../../../Library/physical_constants.h"
-#include "../../../../Library/math_constants.h"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+// Satellite parameters
+#include
static RoughThreeAxisDetermination rough_three_axis_determination_;
const RoughThreeAxisDetermination* const rough_three_axis_determination = &rough_three_axis_determination_;
@@ -169,9 +172,9 @@ AppInfo APP_RTAD_create_app(void)
static void APP_RTAD_init_(void)
{
rough_three_axis_determination_.previous_obc_time = TMGR_get_master_clock();
- rough_three_axis_determination_.method = APP_RTAD_METHOD_TRIAD;
- rough_three_axis_determination_.q_method_info.sun_vec_weight = 0.5f; // TODO_L: サンセンサの観測分散と磁気センサの観測分散で決める
- rough_three_axis_determination_.q_method_info.mag_vec_weight = 1.0f - rough_three_axis_determination_.q_method_info.sun_vec_weight; // TODO_L: サンセンサの観測分散と磁気センサの観測分散で決める
+ rough_three_axis_determination_.method = ATTITUDE_DETERMINATION_PARAMETERS_rtad_method;
+ rough_three_axis_determination_.q_method_info.sun_vec_weight = ATTITUDE_DETERMINATION_PARAMETERS_q_method_sun_vec_weight;
+ rough_three_axis_determination_.q_method_info.mag_vec_weight = 1.0f - rough_three_axis_determination_.q_method_info.sun_vec_weight;
}
static void APP_RTAD_exec_(void)
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.c
index 822f459b..cd4be63b 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.c
@@ -12,13 +12,16 @@
#include
#include "stt_gyro_ekf.h"
-#include "../aocs_manager.h"
-#include "../../../app_registry.h"
-#include "../../../../Library/vector3.h"
-#include "../../../DriverInstances/di_stim210.h"
-#include "../../../DriverInstances/di_sagitta.h"
-#include "../HardwareDependent/SensorFilters/sagitta_filter.h"
-#include "../../../../Library/math_constants.h"
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+// Satellite parameters
+#include
MATRIX_DEFINE_MATRIX_SRTUCT(6, 3, float);
MATRIX_DEFINE_MATRIX_SRTUCT(6, 1, float);
@@ -196,14 +199,21 @@ AppInfo APP_STT_GYRO_EKF_create_app(void)
static void APP_STT_GYRO_EKF_init_(void)
{
- APP_STT_GYRO_EKF_process_noise_covariance_ = MATRIX_MAKE_INIT_MATRIX(6, 6, float);
- // 姿勢変化は制御周期0.1秒間での軌道位相変化と同程度とし,分散はその2乗になる.
- const float kOrbitPeriodSec = 5700.0f; //!< 軌道周期
- stt_gyro_ekf_.process_noise_covariance.attitude_element =
- powf((MATH_CONST_2PI / kOrbitPeriodSec * APP_STT_GYRO_EKF_kComputationCycle_), 2.0f);
- // 姿勢レート変化はどの程度の値にするか未定.
- stt_gyro_ekf_.process_noise_covariance.attitude_rate_element =
- powf((MATH_CONST_2PI / kOrbitPeriodSec * APP_STT_GYRO_EKF_kComputationCycle_), 2.0f);
+ // General parameters
+ APP_STT_GYRO_EKF_calculation_time_.previous = TMGR_get_master_clock();
+ APP_STT_GYRO_EKF_calculation_time_.current = TMGR_get_master_clock();
+ APP_STT_GYRO_EKF_before_stt_unix_time_ms_ = 0;
+
+ stt_gyro_ekf_.estimated_result.quaternion_i2b = QUATERNION_make_unit();
+ VECTOR3_initialize(stt_gyro_ekf_.estimated_result.angular_velocity_body_rad_s, 0.0f);
+ VECTOR3_initialize(stt_gyro_ekf_.estimated_result.rate_bias_body_rad_s, 0.0f);
+
+ stt_gyro_ekf_.use_ekf_estimated_attitude = APP_STT_GYRO_EKF_USE_ESTIMATED_ATTITUDE_DISABLE;
+ stt_gyro_ekf_.calculation_state = APP_STT_GYRO_EKF_CALCULATION_DIVERGED;
+
+ // Process noise model
+ stt_gyro_ekf_.process_noise_covariance.attitude_element = ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude;
+ stt_gyro_ekf_.process_noise_covariance.attitude_rate_element = ATTITUDE_DETERMINATION_PARAMETERS_ekf_process_noise_covariance_attitude_rate;
APP_STT_GYRO_EKF_process_noise_covariance_ = MATRIX_MAKE_INIT_MATRIX(6, 6, float);
for (size_t i = 0; i < PHYSICAL_CONST_THREE_DIM; i++)
{
@@ -211,39 +221,36 @@ static void APP_STT_GYRO_EKF_init_(void)
APP_STT_GYRO_EKF_process_noise_covariance_.data[i + 3][i + 3] = stt_gyro_ekf_.process_noise_covariance.attitude_rate_element;
}
+ // Observation model
APP_STT_GYRO_EKF_observation_matrix_ = MATRIX_MAKE_INIT_MATRIX(3, 6, float);
for (size_t i = 0; i < PHYSICAL_CONST_THREE_DIM; i++)
{
APP_STT_GYRO_EKF_observation_matrix_.data[i][i] = 1.0f;
}
- APP_STT_GYRO_EKF_calculation_time_.previous = TMGR_get_master_clock();
- APP_STT_GYRO_EKF_calculation_time_.current = TMGR_get_master_clock();
- APP_STT_GYRO_EKF_before_stt_unix_time_ms_ = 0;
-
- stt_gyro_ekf_.estimated_result.quaternion_i2b = QUATERNION_make_unit();
- VECTOR3_initialize(stt_gyro_ekf_.estimated_result.angular_velocity_body_rad_s, 0.0f);
- VECTOR3_initialize(stt_gyro_ekf_.estimated_result.rate_bias_body_rad_s, 0.0f);
-
- stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s[0] = 4.363323e-5f; // STIM210ランダムノイズN:15deg/sq(h)
- stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s[1] = 4.363323e-5f; // STIM210ランダムノイズN:15deg/sq(h)
- stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s[2] = 4.363323e-5f; // STIM210ランダムノイズN:15deg/sq(h)
+ // Observation noise model for Gyro sensor
+ VECTOR3_copy(stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s,
+ ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_noise_standard_deviation_compo_rad_s);
QUATERNION_trans_coordinate(stt_gyro_ekf_.gyro_random_noise.standard_deviation_body_rad_s,
- stim210_driver[STIM210_IDX_IN_UNIT]->info.frame_transform_c2b,
- stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s);
+ stim210_driver[STIM210_IDX_IN_UNIT]->info.frame_transform_c2b,
+ stt_gyro_ekf_.gyro_random_noise.standard_deviation_compo_rad_s);
- // ランダムウォークノイズ:STIM210 bias stability B = 0.3deg/h
- stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2[0] = 7.272205e-8f; // K=3/2*B^2/Nとして計算
- stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2[1] = 7.272205e-8f; // K=3/2*B^2/Nとして計算
- stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2[2] = 7.272205e-8f; // K=3/2*B^2/Nとして計算
+ VECTOR3_copy(stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2,
+ ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_standard_deviation_compo_rad_s2);
QUATERNION_trans_coordinate(stt_gyro_ekf_.gyro_random_walk.standard_deviation_body_rad_s2,
- stim210_driver[STIM210_IDX_IN_UNIT]->info.frame_transform_c2b,
- stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2);
+ stim210_driver[STIM210_IDX_IN_UNIT]->info.frame_transform_c2b,
+ stt_gyro_ekf_.gyro_random_walk.standard_deviation_compo_rad_s2);
- // STIM210のノイズは,ECRVよりは単純なランダムウォークノイズとしてモデル化するのが適切.
- // ECRV時定数->無限大の極限がランダムウォークノイズと一致するので,今回は大きな値として10^9で設定する.
- stt_gyro_ekf_.gyro_random_walk.time_constant_s = 1.0E9f;
+ stt_gyro_ekf_.gyro_random_walk.time_constant_s = ATTITUDE_DETERMINATION_PARAMETERS_ekf_gyro_random_walk_time_constant_s;
+ // Observation noise model for Star sensor
+ VECTOR3_copy(stt_gyro_ekf_.stt_error.standard_deviation_compo_rad,
+ ATTITUDE_DETERMINATION_PARAMETERS_ekf_stt_standard_deviation_compo_rad);
+ QUATERNION_trans_coordinate(stt_gyro_ekf_.stt_error.standard_deviation_body_rad,
+ sagitta_driver[SAGITTA_IDX_IN_UNIT]->info.frame_transform_c2b,
+ stt_gyro_ekf_.stt_error.standard_deviation_compo_rad);
+
+ // System matrix
APP_STT_GYRO_EKF_system_matrix_.a = MATRIX_MAKE_INIT_MATRIX(6, 6, float);
APP_STT_GYRO_EKF_system_matrix_.a.data[0][3] = -0.5f;
APP_STT_GYRO_EKF_system_matrix_.a.data[1][4] = -0.5f;
@@ -260,13 +267,7 @@ static void APP_STT_GYRO_EKF_init_(void)
APP_STT_GYRO_EKF_system_matrix_.b.data[4][4] = 1.0f;
APP_STT_GYRO_EKF_system_matrix_.b.data[5][5] = 1.0f;
- stt_gyro_ekf_.stt_error.standard_deviation_compo_rad[0] = 4.8481e-5f; // STT roll方向精度:10秒角
- stt_gyro_ekf_.stt_error.standard_deviation_compo_rad[1] = 9.6963e-6f; // STT cross方向精度:2秒角
- stt_gyro_ekf_.stt_error.standard_deviation_compo_rad[2] = 9.6963e-6f; // STT cross方向精度:2秒角
- QUATERNION_trans_coordinate(stt_gyro_ekf_.stt_error.standard_deviation_body_rad,
- sagitta_driver[SAGITTA_IDX_IN_UNIT]->info.frame_transform_c2b,
- stt_gyro_ekf_.stt_error.standard_deviation_compo_rad);
-
+ // Covariance matrix
stt_gyro_ekf_.initial_covariance.diagonal_component_stt[0] =
powf(stt_gyro_ekf_.stt_error.standard_deviation_body_rad[0], 2.0f);
stt_gyro_ekf_.initial_covariance.diagonal_component_stt[1] =
@@ -277,9 +278,7 @@ static void APP_STT_GYRO_EKF_init_(void)
powf(stt_gyro_ekf_.gyro_random_noise.standard_deviation_body_rad_s[0], 2.0f);
APP_STT_GYRO_EKF_initialize_covariance_matrix_();
- stt_gyro_ekf_.use_ekf_estimated_attitude = APP_STT_GYRO_EKF_USE_ESTIMATED_ATTITUDE_DISABLE;
- stt_gyro_ekf_.calculation_state = APP_STT_GYRO_EKF_CALCULATION_DIVERGED;
-
+ // Observation covariance
APP_STT_GYRO_EKF_observation_noise_covariance_ = MATRIX_MAKE_INIT_MATRIX(3, 3, float);
for (size_t i = 0; i < PHYSICAL_CONST_THREE_DIM; i++)
{
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.h
index 4ec0cff4..81b0c080 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/stt_gyro_ekf.h
@@ -8,9 +8,9 @@
#include
#include
#include
-#include "../../../../Library/quaternion.h"
-#include "../../../../Library/matrix.h"
-#include "../../../../Library/vector3.h"
+#include
+#include
+#include
MATRIX_DEFINE_MATRIX_SRTUCT(6, 6, float);
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.c b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.c
index 82cb62ec..9929509c 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.c
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.c
@@ -8,10 +8,10 @@
#include "sun_vector_propagator.h"
-#include "../../../../Library/vector3.h"
-#include "../../../../Library/matrix33.h"
-#include "../../../../Library/quaternion.h"
-#include "../aocs_manager.h"
+#include
+#include
+#include
+#include
static SunVectorPropagator sun_vector_propagator_;
const SunVectorPropagator* const sun_vector_propagator = &sun_vector_propagator_;
diff --git a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.h b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.h
index 1f260650..79a527bb 100644
--- a/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.h
+++ b/src/src_user/Applications/UserDefined/AOCS/AttitudeDetermination/sun_vector_propagator.h
@@ -10,9 +10,9 @@
#include
#include
#include
-#include "../../../../Library/quaternion.h"
-#include "../../../../Library/physical_constants.h"
-#include "../../AOCS/aocs_error.h"
+#include
+#include
+#include
/**
* @struct SunVectorPropagator
diff --git a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.c b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.c
index 88e44647..ccea52a8 100644
--- a/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.c
+++ b/src/src_user/Applications/UserDefined/AOCS/HardwareDependent/ActuatorControllers/mtq_seiren_controller.c
@@ -13,13 +13,13 @@
#include